diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..e4a8599 --- /dev/null +++ b/.gitignore @@ -0,0 +1,4 @@ +output/* +matlab/paper_data/* +*.mat +*.m~ diff --git a/CMakeLists.txt b/CMakeLists.txt index 05609e1..88b1573 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,22 @@ -cmake_minimum_required (VERSION 2.8.3) -project (lidar_tag) +cmake_minimum_required (VERSION 3.1) +project (lidartag) # CMAKE TWEAKS #======================================================================== -set(CMAKE_CXX_STANDARD 11) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3 -DEIGEN_NO_DEBUG -march=native -Wl,--no-as-needed") +# set(CMAKE_CXX_STANDARD 14) +# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -O3 -DEIGEN_NO_DEBUG -march=native -Wl,--no-as-needed") +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -O3 -DEIGEN_NO_DEBUG -march=native -Wl,--no-as-needed") +# set(MATLAB_INCLUDE_DIRS /usr/local/MATLAB/R2019b/extern/include/) +# set(MATLAB_LIBRARIES_DIRS /usr/local/MATLAB/R2019b/bin/glnxa64) +# set(MATLAB_LIBRARIES ${MATLAB_LIBRARIES_DIRS}/libmat.so ${MATLAB_LIBRARIES_DIRS}/libmx.so) +# list(APPEND CMAKE_PREFIX_PATH "/home/brucebot/softwares/oneTBB") +# list(APPEND CMAKE_PREFIX_PATH "/usr/local/include") +# list(APPEND CMAKE_PREFIX_PATH "/usr/local/lib/cmake") +# list(APPEND CMAKE_PREFIX_PATH "/home/brucebot/softwares/tbb_outsourced/build2") +# set(CMAKE_MODULE_PATH "/home/brucebot/softwares/TBB/build/;/usr/local/lib/;/usr/local/lib/cmake/;${CMAKE_MODULE_PATH}") +LIST(APPEND CMAKE_MODULE_PATH "/home/brucebot/workspace/catkin/src/LiDARTag/cmake/") +message(STATUS "=============================================CMAKE_MODULE_PATH: ${CMAKE_MODULE_PATH}") find_package(catkin REQUIRED COMPONENTS roscpp @@ -19,33 +31,60 @@ find_package(catkin REQUIRED COMPONENTS lidartag_msgs ) # CHECK THE DEPENDENCIES +find_package(NLopt REQUIRED) # PCL find_package(PCL 1.2 REQUIRED) find_package(Boost REQUIRED COMPONENTS filesystem system signals regex date_time program_options thread ) +# find_package(Eigen3) +#include(cmake) +# include(${CMAKE_CURRENT_SOURCE_DIR}/../A/CMakeLists.txt) +# find_package(Eigen3 HINTS /home/brucebot/softwares/eigen_git/cmake/) +# set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +# message(STATUS "=============================================Eigen path: ${EIGEN3_INCLUDE_DIR}") +# set(EIGEN3_INCLUDE_DIR "/usr/local/include/eigen3/") + +message(STATUS "===============================NLOPT lib: ${NLOPT_LIBRARIES}") +find_package(TBB REQUIRED) +if(TBB_FOUND) + message(STATUS "=============================================TBB FOUND") + message(STATUS "===============================TBB include_dirs: ${TBB_INCLUDE_DIRS}") + message(STATUS "===============================TBB includes: ${TBB_INCLUDES}") + message(STATUS "===============================TBB libs: ${TBB_LIBS}") + message(STATUS "===============================TBB libraries: ${TBB_LIBRARIES}") + message(STATUS "===============================TBB libraries: ${TBB_LIBRARIES}") + message(STATUS "===============================TBB libs: ${TBB_LIBS}") + message(STATUS "===============================TBB defs: ${TBB_DEFINITIONS}") +else() + message(STATUS "=============================================TBB NOT FOUND") +endif() + + find_package(Eigen3) if(NOT EIGEN3_FOUND) # Fallback to cmake_modules find_package(cmake_modules REQUIRED) + # message(STATUS "=============================================Eigen path: ${EIGEN3_INCLUDE_DIR}") find_package(Eigen REQUIRED) set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) # Not strictly necessary as Eigen is head only # Possibly map additional variables to the EIGEN3_ prefix. else() + # message(STATUS "=============================================Eigen path: ${EIGEN3_INCLUDE_DIR}") set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) endif() +find_package(Qt5 COMPONENTS Core Widgets REQUIRED) catkin_package( - INCLUDE_DIRS include - CATKIN_DEPENDS - message_filters + INCLUDE_DIRS include + CATKIN_DEPENDS + message_filters roscpp sensor_msgs - std_msgs + std_msgs tf - - DEPENDS + DEPENDS Eigen3 ) @@ -53,19 +92,23 @@ include_directories( include ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} - ${Boost_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} + ${TBB_INCLUDE_DIRS} ) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) # COMPILE THE SOURCE #======================================================================== -add_executable(lidar_tag_main src/main.cc src/lidar_tag.cc src/apriltag_utils.cc src/utils.cc src/tag49h14.cc src/tag16h5.cc) -add_dependencies(lidar_tag_main ${${PROJECT_NAME}_EXPORTED_TARGETS} +add_executable(lidartag_main src/main.cc src/lidartag_pose.cc src/lidartag.cc src/lidartag_decode.cc src/apriltag_utils.cc src/utils.cc src/tag49h14.cc src/tag16h5.cc src/lidartag_rviz.cc src/lidartag_cluster.cc src/lidartag_prune.cc) + +add_dependencies(lidartag_main ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) -target_link_libraries(lidar_tag_main +target_link_libraries(lidartag_main ${catkin_LIBRARIES} ${Boost_LIBRARIES} - ${PCL_LIBRARIES} + ${PCL_LIBRARIES} + ${NLOPT_LIBRARIES} + ${TBB_LIBRARIES} ) diff --git a/LICENSE b/LICENSE.md similarity index 86% rename from LICENSE rename to LICENSE.md index f288702..0ad25db 100644 --- a/LICENSE +++ b/LICENSE.md @@ -1,5 +1,5 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 + GNU AFFERO GENERAL PUBLIC LICENSE + Version 3, 19 November 2007 Copyright (C) 2007 Free Software Foundation, Inc. Everyone is permitted to copy and distribute verbatim copies @@ -7,17 +7,15 @@ Preamble - The GNU General Public License is a free, copyleft license for -software and other kinds of works. + The GNU Affero General Public License is a free, copyleft license for +software and other kinds of works, specifically designed to ensure +cooperation with the community in the case of network server software. The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to +our General Public Licenses are intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. +software for all its users. When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you @@ -26,44 +24,34 @@ them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. + Developers that use our General Public Licenses protect your rights +with two steps: (1) assert copyright on the software, and (2) offer +you this License which gives you legal permission to copy, distribute +and/or modify the software. + + A secondary benefit of defending all users' freedom is that +improvements made in alternate versions of the program, if they +receive widespread use, become available for other developers to +incorporate. Many developers of free software are heartened and +encouraged by the resulting cooperation. However, in the case of +software used on network servers, this result may fail to come about. +The GNU General Public License permits making a modified version and +letting the public access it on a server without ever releasing its +source code to the public. + + The GNU Affero General Public License is designed specifically to +ensure that, in such cases, the modified source code becomes available +to the community. It requires the operator of a network server to +provide the source code of the modified version running there to the +users of that server. Therefore, public use of a modified version, on +a publicly accessible server, gives the public access to the source +code of the modified version. + + An older license, called the Affero General Public License and +published by Affero, was designed to accomplish similar goals. This is +a different license, not a version of the Affero GPL, but Affero has +released a new version of the Affero GPL which permits relicensing under +this license. The precise terms and conditions for copying, distribution and modification follow. @@ -72,7 +60,7 @@ modification follow. 0. Definitions. - "This License" refers to version 3 of the GNU General Public License. + "This License" refers to version 3 of the GNU Affero General Public License. "Copyright" also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. @@ -549,35 +537,45 @@ to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. - 13. Use with the GNU Affero General Public License. + 13. Remote Network Interaction; Use with the GNU General Public License. + + Notwithstanding any other provision of this License, if you modify the +Program, your modified version must prominently offer all users +interacting with it remotely through a computer network (if your version +supports such interaction) an opportunity to receive the Corresponding +Source of your version by providing access to the Corresponding Source +from a network server at no charge, through some standard or customary +means of facilitating copying of software. This Corresponding Source +shall include the Corresponding Source for any work covered by version 3 +of the GNU General Public License that is incorporated pursuant to the +following paragraph. Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single +under version 3 of the GNU General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. +but the work with which it is combined will remain governed by version +3 of the GNU General Public License. 14. Revised Versions of this License. The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to +the GNU Affero General Public License from time to time. Such new versions +will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General +Program specifies that a certain numbered version of the GNU Affero General Public License "or any later version" applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published +GNU Affero General Public License, you may choose any version ever published by the Free Software Foundation. If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's +versions of the GNU Affero General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. @@ -635,40 +633,29 @@ the "copyright" line and a pointer to where the full notice is found. Copyright (C) This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or + it under the terms of the GNU Affero General Public License as published + by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. + GNU Affero General Public License for more details. - You should have received a copy of the GNU General Public License + You should have received a copy of the GNU Affero General Public License along with this program. If not, see . Also add information on how to contact you by electronic and paper mail. - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". + If your software can interact with users remotely through a computer +network, you should also make sure that it provides a way for users to +get its source. For example, if your program is a web application, its +interface could display a "Source" link that leads users to an archive +of the code. There are many ways you could offer source, and different +solutions will be better for different programs; see section 13 for the +specific requirements. You should also get your employer (if you work as a programmer) or school, if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see +For more information on this, and how to apply and follow the GNU AGPL, see . - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. diff --git a/LiDARTag.pdf b/LiDARTag.pdf new file mode 100644 index 0000000..9da27a4 Binary files /dev/null and b/LiDARTag.pdf differ diff --git a/README.md b/README.md index 5cf59ac..52d5dc0 100644 --- a/README.md +++ b/README.md @@ -1,42 +1,353 @@ # LiDARTag + ## Overview +This is a package for LiDARTag, described in paper: **LiDARTag: A Real-Time Fiducial Tag System for Point Clouds** ([PDF](./LiDARTag.pdf))([arXiv](https://arxiv.org/abs/1908.10349)). This work is accepted by IEEE Robotics and Automation Letters and published at ([here](https://ieeexplore.ieee.org/abstract/document/9392337)). + -This is a ROS package for detecting the LiDARTag via ROS. +Image-based fiducial markers are useful in problems such as object tracking in cluttered or textureless environments, camera (and multi-sensor) calibration tasks, and vision-based simultaneous localization and mapping (SLAM). However, the state-of-the-art fiducial marker detection algorithms rely on the consistency of the ambient lighting. To the best of our knowledge, there are no existing fiducial markers for point clouds. -* Author: Bruce JK Huang +This paper introduces LiDARTag, a novel fiducial tag design and detection algorithm suitable for LiDAR point clouds. The proposed method runs in real-time and can process data at 100 Hz, which is faster than the currently available LiDAR sensor frequencies. Additionally, the software works with different marker sizes in cluttered indoors and spacious outdoors, even when it is entirely dark. Because of the LiDAR sensors' nature, rapidly changing ambient lighting will not affect the detection of a LiDARTag. Therefore, LiDARTag can be used in tandem with camera-based markers to address the issue of images being sensitive to ambient lighting. + +* Author: Jiunn-Kai (Bruce) Huang, Shoutian Wang, Maani Ghaffari, and Jessy W. Grizzle * Maintainer: [Bruce JK Huang](https://www.brucerobot.com/), brucejkh[at]gmail.com * Affiliation: [The Biped Lab](https://www.biped.solutions/), the University of Michigan -This package has been tested under [ROS] Kinetic and Ubuntu 16.04. -More detail introduction will be update shortly. Sorry for the inconvenient! +This package has been tested under [ROS] Melodic and Ubuntu 18.04.\ +**[Note]** More detailed introduction will be updated shortly. Sorry for the inconvenient!\ +**[Issues]** If you encounter _any_ issues, I would be happy to help. If you cannot find a related one in the existing issues, please open a new one. I will try my best to help! + + +## Abstract +Image-based fiducial markers are useful in problems such as object tracking in cluttered or textureless environments, camera (and multi-sensor) calibration tasks, and vision-based simultaneous localization and mapping (SLAM). The state-of-the-art fiducial marker detection algorithms rely on the consistency of the ambient lighting. This paper introduces LiDARTag, a novel fiducial tag design and detection algorithm suitable for light detection and ranging (LiDAR) point clouds. The proposed method runs in real-time and can process data at 100 Hz, which is faster than the currently available LiDAR sensor frequencies. Because of the LiDAR sensors' nature, rapidly changing ambient lighting will not affect the detection of a LiDARTag; hence, the proposed fiducial marker can operate in a completely dark environment. In addition, the LiDARTag nicely complements and is compatible with existing visual fiducial markers, such as AprilTags, allowing for efficient multi-sensor fusion and calibration tasks. We further propose a concept of minimizing a fitting error between a point cloud and the marker's template to estimate the marker's pose. The proposed method achieves millimeter error in translation and a few degrees in rotation. Due to LiDAR returns' sparsity, the point cloud is lifted to a continuous function in a reproducing kernel Hilbert space where the inner product can be used to determine a marker's ID. The experimental results, verified by a motion capture system, confirm that the proposed method can reliably provide a tag's pose and unique ID code. The rejection of false positives is validated on the [Google Cartographer](https://google-cartographer-ros.readthedocs.io/en/latest/data.html) dataset and the outdoor [Honda H3D](https://usa.honda-ri.com/H3D) datasets. All implementations are coded in C++ and are available at: [https://github.com/UMich-BipedLab/LiDARTag](https://github.com/UMich-BipedLab/LiDARTag). + + +## Video +Please checkout the introduction [video](https://www.brucerobot.com/lidartag). It highlights some important keypoints in the paper! +[](https://www.brucerobot.com/lidartag) + + ## Quick View - - +LiDAR-based markers can be used in tandem with camera-based markers to address the issue of images being sensitive to ambient lighting. LiDARTags have been successfully applied to LiDAR-camera extrinsic calibration ([paper](https://ieeexplore.ieee.org/document/9145571), [GitHub](https://github.com/UMich-BipedLab/extrinsic_lidar_camera_calibration)). This figure shows a visualization of LiDARTags of two different sizes in a full point cloud scan. + +This system runs in real-time (over 100 Hz) while handling a full scan of the point cloud; it achieves millimeter accuracy in translation and a few degrees of error in rotation. The tag decoding accuracy is 99.7%. + + + + +## Why LiDAR? +Robust to lighting!! The following shows LiDARTags are detected in several challenging lighting conditions: +##### Dingy environment + + +##### Completely dark environment + + +##### Half tag being overexposed + + +##### Rapid changing ambient light + + +## Overall pipeline +The system contains three parts: tag detection, pose estimation, and tag decoding. The detection step takes an entire LiDAR scan (up to 120,000 points from a 32-Beam Velodyne ULTRA Puck LiDAR) and outputs collections of likely payload points of the LiDARTag. Next, a tag's optimal pose minimizes the -inspired cost in (8), though the rotation of the tag about a normal vector to the tag may be off by or and will be resolved in the decoding process. The tag's ID is decoded with a pre-computed function library. The decoded tag removes the rotation ambiguity about the normal. + + + + +## Package Analysis +We present performance evaluations of the LiDARTag where ground truth data are provided by a motion capture system with 30 motion capture cameras. We also extensively analyze each step in the system with spacious outdoor and cluttered indoor environments. Additionally, we report the rate of false positives validated on the indoor [Google Cartographer](https://google-cartographer-ros.readthedocs.io/en/latest/data.html) dataset and the outdoor [Honda H3D](https://usa.honda-ri.com/H3D) datasets. + +#### Pose and Decoding Analysis +Decoding accuracy of the RKHS method and pose accuracy of the fitting method. The ground truth is provided by a motion capture system with 30 motion capture cameras. The distance is in meters. The translation error is in millimeters and rotation error is the misalignment angle, (23), in degrees. + + +#### Computation Time of Each Step Analysis +This table averages all the datasets we collected and describes computation time of each step for indoors and outdoors. + + + +### Cluster Rejection Analysis +This table takes into account all the data we collected and shows numbers of rejected clusters in each step in different scenes. Additionally, we also report false positive rejection for [Google Cartographer](https://google-cartographer-ros.readthedocs.io/en/latest/data.html) dataset and [Honda H3D](https://usa.honda-ri.com/H3D) datasets. + + +#### Double-Sum Analysis +The original double sum in (18) is too slow to achieve a real-time application. This table compares different methods to compute the double sum, in which the TBB stands for Threading Building Blocks library from Intel. Additionally, we also apply a k-d tree data structure to speed up the querying process; the k-d tree, however, does not produce fast enough results. The unit in the table is milliseconds. + + +#### False Positives Analysis +This table shows the numbers of false positive rejection of the proposed algorithm. We validated the rejection rate on the indoor [Google Cartographer](https://google-cartographer-ros.readthedocs.io/en/latest/data.html) dataset and the outdoor [Honda H3D](https://usa.honda-ri.com/H3D) datasets. The former has two VLP-16 Velodyne LiDAR and the latter has one 64-beam Velodyne LiDAR. + + +## Required Libraries / Packages +Those are the packages used in the LiDARTag package. It seems many but if you follow my steps, it should take you no more than 30 mins to instal them (including building time!). It took me awhile to get everything right. I summarize how I installed them [here](#installation-of-related-libraries). However, you may choose any way you want to install them. +1. Please install [ROS Melodic](http://wiki.ros.org/melodic/Installation/Ubuntu). +2. Please install [TBB library](https://github.com/oneapi-src/oneTBB). You may need to modify the CMakeLists.txt according to your installation. +3. Please install [NLopt](https://nlopt.readthedocs.io/en/latest/). You may need to midify the CMakeLists.txt according to your installation. +4. Please download [LiDARTag_msgs](https://github.com/UMich-BipedLab/LiDARTag_msgs) and place them under your catkin workspace. +5. Plesae ensure you have a correct Eigen Library on your system by downloading it from the [GitLab](https://gitlab.com/libeigen/eigen.git) and checkout `6f0f6f792e441c32727ed945686fefe02e6bdbc6`. Any commit older than this should also work. + +## Installation of Related Libraries +### ROS Melodic +Please directly follow the instruction on the official website ([here](http://wiki.ros.org/melodic/Installation/Ubuntu)). + +### TBB library +###### Installation +Original TBB package from Intel does not support CMake; I, therefore, use another repository that supports CMake to make my life easier. +``` +git clone https://github.com/wjakob/tbb +mkdir build; +cd build; +cmake ..; +cmake --build . --config Release -- -j 6; +sudo cmake --build . --target install +``` + +###### Notes +Ensure the followings in the CMakeList.txt are correct: +1. FindTBB.cmake is under _LiDARTag/cmake/_ +2. LIST(APPEND CMAKE_MODULE_PATH "YOUR_PATH/LiDARTag/cmake/") + * Please change **YOUR_PATH** to your path to the LiDARTag package (something like this: catkin/src/LiDARTag/cmake). + + +### NLopt library +###### Installation +Please direct follow the instruction on the official website ([here](https://nlopt.readthedocs.io/en/latest/NLopt_Installation/)) or as follow: +``` +git clone git://github.com/stevengj/nlopt +cd nlopt +mkdir build +cd build +cmake .. +make +sudo make install +``` + +### LiDARTag package +1. Once you place LiDARTag_msgs under your catkin workspace and installed all the required libraries, you can directly `catkin_make` the package. +2. `source devel/setup.bash` +3. `roslaunch lidartag LiDARTag_twotags.launch` +4. `rosbag play -l -q bagfile.bag` + + + +## Datasets and Results +### Quantitative results: +If you would like to see how the tables in the paper are generated, please follow as below: +1. Download [this folder](https://drive.google.com/drive/folders/16bJx_Hc7iqy5-rxjWVgXOhvJGULu4hI9?usp=sharing). +2. Put them under _LiDARTag/matlab/paper_data/_ +3. Run _genTable.m_ located at _LiDARTag/matlab/_ + + +To regenerate results on the paper from scratch, please download the two datasets below: +1. Please download bagfiles from [here](https://drive.google.com/drive/folders/1k-p3q2hl1ZRIcle1lfcS0AN-DAK91RMw?usp=sharing). +2. Please download motion capture data from [here](https://drive.google.com/drive/folders/1rWCRsktFPZiOyQopwG7vCXatqwU-EyFb?usp=sharing) +3. change the _output_path_ in the launch file +4. `roslaunch lidartag LiDARTag_threetags.launch` + +###### Note +The target sizes in the quantitative result folder are 1.22. + +### Qualitative results: +1. Please download bagfiles from [here](https://drive.google.com/drive/folders/19w13uJNMax9_fNIzmFZwzYq2LpJsjKKh?usp=sharing). +2. `roslaunch lidartag LiDARTag_twotags.launch` + +###### Note +The target sizes in the qualitative result folder are 0.8051, 0.61. + + +### False positive rejection: +Please download [Google Cartographer](https://google-cartographer-ros.readthedocs.io/en/latest/data.html) dataset and [Honda H3D](https://usa.honda-ri.com/H3D) datasets. +We also provide different launch files (cartographer.launch, H3D.launch) for different datasets due to different published LiDAR topics and different _output_path_. I also wrote my own parsing script to pass bin files to rosbag. Please let me know if anyone needs it. + + +## Running +1. Please download qualitative bagfiles from [here](https://drive.google.com/drive/folders/19w13uJNMax9_fNIzmFZwzYq2LpJsjKKh?usp=sharing). +2. `catkin_make` the package. +3. `source devel/setup.bash` +4. `roslaunch lidartag LiDARTag_twotags.launch` +5. `rosbag play -l -q bagfile.bag` +6. To see the results, `rosrun rviz rviz`. You can directly open _LiDARTag.rviz_ under _LiDARTag/rviz/_ folder. + + +###### Notes +This package provides several launch files that you can directly run the package.\ +Please remember to change the **tag_size_list** in a launch file according to your target sizes or which bag file you are playing, or what marker sizes you have.\ +Different launch files:\ +-- LiDARTag_smallest.launch: only the smallest tag (0.61)\ +-- LiDARTag_twotags.launch: two smaller tags (0.61, 0.8)\ +-- LiDARTag_threetags.launch: all tags (0.8, 0.61, 1.22)\ +Please note that, the clearance around the markers should larger than , where is the size of the **largest** marker. Therefore, it is recommended to use smaller tags in indoor environments. + + + +## Building Your Markers + \ +We provide tag16h6c5 from AprilTag3 with three sizes (0.61, 0.85, 1.2).\ +If you want to use the provided markers, it is easy: +1. Attach a fiducial marker to a squared cardboard or plexiglass and place the marker inside the yellow region. + * Note: The sizes **must be** one of 0.61, 0.805, 1.22 meter, or you **have to** regenerate the function dictionary. If so, please follow [here](#building-your-own-customized-markers). +2. Find a 3D object to _support_ your marker. It could be a box or an easel. + * Please note that, the clearance around the markers should larger than , where is the size of the **largest** marker. Therefore, it is recommended to use smaller tags in indoor environments. +4. Follow [these steps](#running) to run the package. + +## Building Your Own Customized Markers +If you would like to use your own customized markers (i.e. different types of markers or different sizes), please follow these steps:\ +I. Build your function dictionary: +1. `git clone https://github.com/UMich-BipedLab/matlab_utils` +2. Add _matlab_utils_ into _build_LiDARTag_library.m_ or add _matlab_utils_ into your MATLAB path. +3. Edit **opts.img_path** in _build_LiDARTag_library.m_ according to where you put images of your fiducial markers. +4. Measure the size of your marker () +5. Open _build_LiDARTag_library.m_ in _LiDARTag/matlab/function_dictionary/_. Change `opts.target_size_` to your marker size and run _build_LiDARTag_library.m_ to generate your function library. +6. Put the generated function dictuionary into _LiDARTag/lib/_ +7. When placing the generated function dictionary in _LiDARTag/lib/_, please put different sizes into different sub-folders (0, 1, 2, 3, ...) and put them in ascending order. For example, if you have three sizes (0.6, 0.8, 1.2), then you will have three sub-folders (0, 1, 2) inside the _lib/_ folder. Please place them as follow: + - LiDARTag/lib/0/: put 0.6-size here + - LiDARTag/lib/1/: put 0.8-size here + - LiDARTag/lib/2/: put 1.2-size here + +II. Follow [Building Your Markers](#building-your-markers) +###### Note +All the functions that are used for testing RKHS are all released in _LiDARTag/matlab/function_dictionary/_ + + +## Parameters of launch files +We split the parameters to two different launch files: `LiDARTag_outdoor.launch` and +`LiDARTag_master.launch.` The front contains the most common tunables for different +environments such as indoor or outdoor. The latter includes more parameters that you +usually need to change for your system only once and just leave them there. +### LiDARTag_outdoor.launch +##### feature clustering +* nearby_factor + Value used to determine if two points are near to each other +* linkage_tunable + Value used to compute the linkage criteria + +##### cluster validation +* max_outlier_ratio + Value used to validate clusters during checking outliers in plane fitting +* tag_size_list + List of possible sizes of tag + +### LiDARTag_master.launch +#### System Mode +* mark_cluster_validity + whether to validate clusters according to different conditions +* plane_fitting + whether to validate clusters according to the result of plane_fitting +* optimize_pose + Whether to optimize poses via reducing the cost function +* decode_id + Whether to decode IDs +* collect_data + Whether to publish detected PCs +* num_threads + The number of threads used for TBB +* print_info + Whether to log status in ros_info_stream + +#### Debugging Mode +* debug_info + Whether to log debug information in ros_debug_stream +* debug_time + Whether to compute time for different parts +* debug_decoding_time + Whether to log time for decoding IDs +* log_data + Whether to save status information into txt file + +#### LiDAR Specification +* has_ring + Whether input data has ring information for each point +* estimate_ring + Whether to estimate ring number for each point -# Why LiDAR? -Robust to lighting!! - - - +#### Solvers for Pose Optimization +* optimization_solver (default: 8) + Which optimization solver to use for optimizing the cost function of a pose. + * Below is numerical gradient-based methods + 1: opt_method = nlopt::LN_PRAXIS; + 2: opt_method = nlopt::LN_NEWUOA_BOUND; + 3: opt_method = nlopt::LN_SBPLX; // recommended + 4: opt_method = nlopt::LN_BOBYQA; + 5: opt_method = nlopt::LN_NELDERMEAD; + 6: opt_method = nlopt::LN_COBYLA; + * Below is analytical gradient-based methods + 7: opt_method = nlopt::LD_SLSQP; // recommended 200Hz + 8: opt_method = nlopt::LD_MMA; // recommended 120Hz + 9: opt_method = nlopt::LD_TNEWTON_PRECOND_RESTART; // fail 90% + 10: opt_method = nlopt::LD_TNEWTON_PRECOND; // fail 90% + 11: opt_method = nlopt::LD_TNEWTON_RESTART; // fail 80% + 12: opt_method = nlopt::LD_TNEWTON; // fail 90% + 13: opt_method = nlopt::LD_LBFGS; // fail 90% + 14: opt_method = nlopt::LD_VAR1; // fail 90% + 15: opt_method = nlopt::LD_VAR2; // fail 90% +* euler_derivative + Whether to use euler derivative or lie group derivative in optimization +* optimize_up_bound + Value used for constraints in optimization +* optimize_low_bound + Value used for constraints in optimization +#### Decode Method +* decode_method (default: 2) + Which decoding method to use: + 0: naive decoder + 1: Weighted Gaussian + 2: RKHS +* decode_mode (default: 5) + Which mode to use: + 0: single thread: original double sum + 1: single thread: convert to matrices + 2: single thread: convert matrices to vectors + 3: c++ thread (works for each point for a thread but not for blobs of points for a thread) + 4: Multi-threading: Original double sum using TBB + 5: Multi-threading: Vector form using TBB without scheduling + 6: Multi-threading: Vector form using TBB with manual scheduling + 7: Multi-threading: Vector form using TBB with TBB scheduling + 8: Single thread: using KDTree -## Presentation and Video -https://www.brucerobot.com/lidartag +#### Tunable +##### feature clustering +* distance_bound + Value used to construct a cube and only detect the tag inside this cube +* depth_bound + Value used to detect feature points compared with depth gradients +* num_points_for_plane_feature + number of points used for detection of feature points -## Installation -TODO +##### cluster validation +* min_return_per_grid + Minimum number of points in each grid (below this number, the cluster will be invalid) +* optimize_percentage + Value used to validate the result of pose estimation via checking cost value +* payload_intensity_threshold + Value used to detect boundary points on the cluster via intensity gradient +* points_threshold_factor +* distance_to_plane_threshold + Value used for plane fitting for a cluster +* minimum_ring_boundary_points + Minimum number of boundary points on each ring in the cluster +* coa_tunable + Value used to validate the result of pose estimation via checking coverage area +* tagsize_tunable + Value used to estimate the size of tag -## Parameters -TODO -## Examples -TODO ## Citations -The LiDARTag is described in: +The detail is described in: **LiDARTag: A Real-Time Fiducial Tag for Point Clouds,** Jiunn-Kai Huang, Shoutian Wang, Maani Ghaffari, and Jessy W. Grizzle. ([PDF](./LiDARTag.pdf)) ([arXiv](https://arxiv.org/abs/1908.10349)) ([here](https://ieeexplore.ieee.org/abstract/document/9392337)) -*Jiunn-Kai Huang, Maani Ghaffari, Ross Hartley, Lu Gan, Ryan M. Eustice and Jessy W. Grizzle “LiDARTag: A Real-Time Fiducial Tag using Point Clouds” (under review) +``` +@ARTICLE{HuangLiDARTag2020, + author={Huang, Jiunn-Kai and Wang, Shoutian and Ghaffari, Maani and Grizzle, Jessy W.}, + journal={IEEE Robotics and Automation Letters}, + title={LiDARTag: A Real-Time Fiducial Tag System for Point Clouds}, + year={2021}, + volume={6}, + number={3}, + pages={4875-4882}, + doi={10.1109/LRA.2021.3070302}} +``` diff --git a/cmake/FindTBB.cmake b/cmake/FindTBB.cmake new file mode 100644 index 0000000..9128d34 --- /dev/null +++ b/cmake/FindTBB.cmake @@ -0,0 +1,304 @@ +# The MIT License (MIT) +# +# Copyright (c) 2015 Justus Calvin +# +# 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. + +# +# FindTBB +# ------- +# +# Find TBB include directories and libraries. +# +# Usage: +# +# find_package(TBB [major[.minor]] [EXACT] +# [QUIET] [REQUIRED] +# [[COMPONENTS] [components...]] +# [OPTIONAL_COMPONENTS components...]) +# +# where the allowed components are tbbmalloc and tbb_preview. Users may modify +# the behavior of this module with the following variables: +# +# * TBB_ROOT_DIR - The base directory the of TBB installation. +# * TBB_INCLUDE_DIR - The directory that contains the TBB headers files. +# * TBB_LIBRARY - The directory that contains the TBB library files. +# * TBB__LIBRARY - The path of the TBB the corresponding TBB library. +# These libraries, if specified, override the +# corresponding library search results, where +# may be tbb, tbb_debug, tbbmalloc, tbbmalloc_debug, +# tbb_preview, or tbb_preview_debug. +# * TBB_USE_DEBUG_BUILD - The debug version of tbb libraries, if present, will +# be used instead of the release version. +# +# Users may modify the behavior of this module with the following environment +# variables: +# +# * TBB_INSTALL_DIR +# * TBBROOT +# * LIBRARY_PATH +# +# This module will set the following variables: +# +# * TBB_FOUND - Set to false, or undefined, if we haven’t found, or +# don’t want to use TBB. +# * TBB__FOUND - If False, optional part of TBB sytem is +# not available. +# * TBB_VERSION - The full version string +# * TBB_VERSION_MAJOR - The major version +# * TBB_VERSION_MINOR - The minor version +# * TBB_INTERFACE_VERSION - The interface version number defined in +# tbb/tbb_stddef.h. +# * TBB__LIBRARY_RELEASE - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. +# * TBB__LIBRARY_DEGUG - The path of the TBB release version of +# , where may be tbb, tbb_debug, +# tbbmalloc, tbbmalloc_debug, tbb_preview, or +# tbb_preview_debug. +# +# The following varibles should be used to build and link with TBB: +# +# * TBB_INCLUDE_DIRS - The include directory for TBB. +# * TBB_LIBRARIES - The libraries to link against to use TBB. +# * TBB_LIBRARIES_RELEASE - The release libraries to link against to use TBB. +# * TBB_LIBRARIES_DEBUG - The debug libraries to link against to use TBB. +# * TBB_DEFINITIONS - Definitions to use when compiling code that uses +# TBB. +# * TBB_DEFINITIONS_RELEASE - Definitions to use when compiling release code that +# uses TBB. +# * TBB_DEFINITIONS_DEBUG - Definitions to use when compiling debug code that +# uses TBB. +# +# This module will also create the "tbb" target that may be used when building +# executables and libraries. + +include(FindPackageHandleStandardArgs) + +if(NOT TBB_FOUND) + + ################################## + # Check the build type + ################################## + + if(NOT DEFINED TBB_USE_DEBUG_BUILD) + if(CMAKE_BUILD_TYPE MATCHES "(Debug|DEBUG|debug|RelWithDebInfo|RELWITHDEBINFO|relwithdebinfo)") + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() + elseif(TBB_USE_DEBUG_BUILD) + set(TBB_BUILD_TYPE DEBUG) + else() + set(TBB_BUILD_TYPE RELEASE) + endif() + + ################################## + # Set the TBB search directories + ################################## + + # Define search paths based on user input and environment variables + set(TBB_SEARCH_DIR ${TBB_ROOT_DIR} $ENV{TBB_INSTALL_DIR} $ENV{TBBROOT}) + + # Define the search directories based on the current platform + if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(TBB_DEFAULT_SEARCH_DIR "C:/Program Files/Intel/TBB" + "C:/Program Files (x86)/Intel/TBB") + + # Set the target architecture + if(CMAKE_SIZEOF_VOID_P EQUAL 8) + set(TBB_ARCHITECTURE "intel64") + else() + set(TBB_ARCHITECTURE "ia32") + endif() + + # Set the TBB search library path search suffix based on the version of VC + if(WINDOWS_STORE) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11_ui") + elseif(MSVC14) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc14") + elseif(MSVC12) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc12") + elseif(MSVC11) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc11") + elseif(MSVC10) + set(TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc10") + endif() + + # Add the library path search suffix for the VC independent version of TBB + list(APPEND TBB_LIB_PATH_SUFFIX "lib/${TBB_ARCHITECTURE}/vc_mt") + + elseif(CMAKE_SYSTEM_NAME STREQUAL "Darwin") + # OS X + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") + + # TODO: Check to see which C++ library is being used by the compiler. + if(NOT ${CMAKE_SYSTEM_VERSION} VERSION_LESS 13.0) + # The default C++ library on OS X 10.9 and later is libc++ + set(TBB_LIB_PATH_SUFFIX "lib/libc++" "lib") + else() + set(TBB_LIB_PATH_SUFFIX "lib") + endif() + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux") + # Linux + set(TBB_DEFAULT_SEARCH_DIR "/opt/intel/tbb") + # set(TBB_DEFAULT_SEARCH_DIR "/home/brucebot/softwares/intel_parallel_studio/tbb") + + # TODO: Check compiler version to see the suffix should be /gcc4.1 or + # /gcc4.1. For now, assume that the compiler is more recent than + # gcc 4.4.x or later. + if(CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(TBB_LIB_PATH_SUFFIX "lib/intel64/gcc4.4") + elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "^i.86$") + set(TBB_LIB_PATH_SUFFIX "lib/ia32/gcc4.4") + endif() + endif() + + ################################## + # Find the TBB include dir + ################################## + + find_path(TBB_INCLUDE_DIRS tbb/tbb.h + HINTS ${TBB_INCLUDE_DIR} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} + PATH_SUFFIXES include) + + ################################## + # Set version strings + ################################## + + if(TBB_INCLUDE_DIRS) + file(READ "${TBB_INCLUDE_DIRS}/tbb/tbb_stddef.h" _tbb_version_file) + string(REGEX REPLACE ".*#define TBB_VERSION_MAJOR ([0-9]+).*" "\\1" + TBB_VERSION_MAJOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_VERSION_MINOR ([0-9]+).*" "\\1" + TBB_VERSION_MINOR "${_tbb_version_file}") + string(REGEX REPLACE ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" + TBB_INTERFACE_VERSION "${_tbb_version_file}") + set(TBB_VERSION "${TBB_VERSION_MAJOR}.${TBB_VERSION_MINOR}") + endif() + + ################################## + # Find TBB components + ################################## + + if(TBB_VERSION VERSION_LESS 4.3) + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc tbb) + else() + set(TBB_SEARCH_COMPOMPONENTS tbb_preview tbbmalloc_proxy tbbmalloc tbb) + endif() + + # Find each component + foreach(_comp ${TBB_SEARCH_COMPOMPONENTS}) + if(";${TBB_FIND_COMPONENTS};tbb;" MATCHES ";${_comp};") + + # Search for the libraries + find_library(TBB_${_comp}_LIBRARY_RELEASE ${_comp} + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) + + find_library(TBB_${_comp}_LIBRARY_DEBUG ${_comp}_debug + HINTS ${TBB_LIBRARY} ${TBB_SEARCH_DIR} + PATHS ${TBB_DEFAULT_SEARCH_DIR} ENV LIBRARY_PATH + PATH_SUFFIXES ${TBB_LIB_PATH_SUFFIX}) + + if(TBB_${_comp}_LIBRARY_DEBUG) + list(APPEND TBB_LIBRARIES_DEBUG "${TBB_${_comp}_LIBRARY_DEBUG}") + endif() + if(TBB_${_comp}_LIBRARY_RELEASE) + list(APPEND TBB_LIBRARIES_RELEASE "${TBB_${_comp}_LIBRARY_RELEASE}") + endif() + if(TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE} AND NOT TBB_${_comp}_LIBRARY) + set(TBB_${_comp}_LIBRARY "${TBB_${_comp}_LIBRARY_${TBB_BUILD_TYPE}}") + endif() + + if(TBB_${_comp}_LIBRARY AND EXISTS "${TBB_${_comp}_LIBRARY}") + set(TBB_${_comp}_FOUND TRUE) + else() + set(TBB_${_comp}_FOUND FALSE) + endif() + + # Mark internal variables as advanced + mark_as_advanced(TBB_${_comp}_LIBRARY_RELEASE) + mark_as_advanced(TBB_${_comp}_LIBRARY_DEBUG) + mark_as_advanced(TBB_${_comp}_LIBRARY) + + endif() + endforeach() + + ################################## + # Set compile flags and libraries + ################################## + + set(TBB_DEFINITIONS_RELEASE "") + set(TBB_DEFINITIONS_DEBUG "-DTBB_USE_DEBUG=1") + + if(TBB_LIBRARIES_${TBB_BUILD_TYPE}) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_${TBB_BUILD_TYPE}}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_${TBB_BUILD_TYPE}}") + elseif(TBB_LIBRARIES_RELEASE) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_RELEASE}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_RELEASE}") + elseif(TBB_LIBRARIES_DEBUG) + set(TBB_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}") + set(TBB_LIBRARIES "${TBB_LIBRARIES_DEBUG}") + endif() + + find_package_handle_standard_args(TBB + REQUIRED_VARS TBB_INCLUDE_DIRS TBB_LIBRARIES + HANDLE_COMPONENTS + VERSION_VAR TBB_VERSION) + + ################################## + # Create targets + ################################## + + if(NOT CMAKE_VERSION VERSION_LESS 3.0 AND TBB_FOUND) + add_library(tbb SHARED IMPORTED) + set_target_properties(tbb PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES ${TBB_INCLUDE_DIRS} + IMPORTED_LOCATION ${TBB_LIBRARIES}) + if(TBB_LIBRARIES_RELEASE AND TBB_LIBRARIES_DEBUG) + set_target_properties(tbb PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "$<$,$>:TBB_USE_DEBUG=1>" + IMPORTED_LOCATION_DEBUG ${TBB_LIBRARIES_DEBUG} + IMPORTED_LOCATION_RELWITHDEBINFO ${TBB_LIBRARIES_DEBUG} + IMPORTED_LOCATION_RELEASE ${TBB_LIBRARIES_RELEASE} + IMPORTED_LOCATION_MINSIZEREL ${TBB_LIBRARIES_RELEASE} + ) + elseif(TBB_LIBRARIES_RELEASE) + set_target_properties(tbb PROPERTIES IMPORTED_LOCATION ${TBB_LIBRARIES_RELEASE}) + else() + set_target_properties(tbb PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${TBB_DEFINITIONS_DEBUG}" + IMPORTED_LOCATION ${TBB_LIBRARIES_DEBUG} + ) + endif() + endif() + + mark_as_advanced(TBB_INCLUDE_DIRS TBB_LIBRARIES) + + unset(TBB_ARCHITECTURE) + unset(TBB_BUILD_TYPE) + unset(TBB_LIB_PATH_SUFFIX) + unset(TBB_DEFAULT_SEARCH_DIR) + +endif() diff --git a/figure/ClusterRemoval.png b/figure/ClusterRemoval.png new file mode 100644 index 0000000..6986beb Binary files /dev/null and b/figure/ClusterRemoval.png differ diff --git a/figure/CompletelyDark.gif b/figure/CompletelyDark.gif new file mode 100644 index 0000000..d7e3839 Binary files /dev/null and b/figure/CompletelyDark.gif differ diff --git a/figure/Dingy.gif b/figure/Dingy.gif new file mode 100644 index 0000000..e13e2ae Binary files /dev/null and b/figure/Dingy.gif differ diff --git a/figure/DoubleSum.png b/figure/DoubleSum.png new file mode 100644 index 0000000..83f01d5 Binary files /dev/null and b/figure/DoubleSum.png differ diff --git a/figure/FalsePositives.png b/figure/FalsePositives.png new file mode 100644 index 0000000..aafeb81 Binary files /dev/null and b/figure/FalsePositives.png differ diff --git a/figure/HalfOverExposured.gif b/figure/HalfOverExposured.gif new file mode 100644 index 0000000..19134c8 Binary files /dev/null and b/figure/HalfOverExposured.gif differ diff --git a/figure/LiDARTagAnalysis.png b/figure/LiDARTagAnalysis.png new file mode 100644 index 0000000..abc7800 Binary files /dev/null and b/figure/LiDARTagAnalysis.png differ diff --git a/figure/LiDARTagFrontView.png b/figure/LiDARTagFrontView.png new file mode 100644 index 0000000..1160227 Binary files /dev/null and b/figure/LiDARTagFrontView.png differ diff --git a/figure/LiDARTagIntro.png b/figure/LiDARTagIntro.png new file mode 100644 index 0000000..153749e Binary files /dev/null and b/figure/LiDARTagIntro.png differ diff --git a/figure/LiDARTagSideView.png b/figure/LiDARTagSideView.png new file mode 100644 index 0000000..baaa310 Binary files /dev/null and b/figure/LiDARTagSideView.png differ diff --git a/figure/LiDARTagVideoImg.png b/figure/LiDARTagVideoImg.png new file mode 100644 index 0000000..97a36b5 Binary files /dev/null and b/figure/LiDARTagVideoImg.png differ diff --git a/figure/MarkerExample2.png b/figure/MarkerExample2.png new file mode 100644 index 0000000..fdaa510 Binary files /dev/null and b/figure/MarkerExample2.png differ diff --git a/figure/PipelineSpeedAnalysis.png b/figure/PipelineSpeedAnalysis.png new file mode 100644 index 0000000..c036b20 Binary files /dev/null and b/figure/PipelineSpeedAnalysis.png differ diff --git a/figure/Pipelinev3.png b/figure/Pipelinev3.png new file mode 100644 index 0000000..23260f2 Binary files /dev/null and b/figure/Pipelinev3.png differ diff --git a/figure/Pose.png b/figure/Pose.png new file mode 100644 index 0000000..54b6902 Binary files /dev/null and b/figure/Pose.png differ diff --git a/figure/RapidShort.gif b/figure/RapidShort.gif new file mode 100644 index 0000000..82363bb Binary files /dev/null and b/figure/RapidShort.gif differ diff --git a/figure/first_fig1.png b/figure/first_fig1.png new file mode 100644 index 0000000..ff49232 Binary files /dev/null and b/figure/first_fig1.png differ diff --git a/figure/first_fig2.jpg b/figure/first_fig2.jpg new file mode 100644 index 0000000..b3bd2bd Binary files /dev/null and b/figure/first_fig2.jpg differ diff --git a/figure/pipeline.png b/figure/pipeline.png new file mode 100644 index 0000000..227fee4 Binary files /dev/null and b/figure/pipeline.png differ diff --git a/if_no_ring.odt b/if_no_ring.odt new file mode 100644 index 0000000..ea7d5d5 Binary files /dev/null and b/if_no_ring.odt differ diff --git a/include/KDTreeVectorOfVectorsAdaptor.h b/include/KDTreeVectorOfVectorsAdaptor.h new file mode 100644 index 0000000..0d4cef4 --- /dev/null +++ b/include/KDTreeVectorOfVectorsAdaptor.h @@ -0,0 +1,117 @@ +/*********************************************************************** + * Software License Agreement (BSD License) + * + * Copyright 2011-16 Jose Luis Blanco (joseluisblancoc@gmail.com). + * 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 AUTHOR ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY + * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (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 "nanoflann.hpp" + +#include + +// ===== This example shows how to use nanoflann with these types of containers: ======= +//typedef std::vector > my_vector_of_vectors_t; +//typedef std::vector my_vector_of_vectors_t; // This requires #include +// ===================================================================================== + + +/** A simple vector-of-vectors adaptor for nanoflann, without duplicating the storage. + * The i'th vector represents a point in the state space. + * + * \tparam DIM If set to >0, it specifies a compile-time fixed dimensionality for the points in the data set, allowing more compiler optimizations. + * \tparam num_t The type of the point coordinates (typically, double or float). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. + * \tparam IndexType The type for indices in the KD-tree index (typically, size_t of int) + */ +template +struct KDTreeVectorOfVectorsAdaptor +{ + typedef KDTreeVectorOfVectorsAdaptor self_t; + typedef typename Distance::template traits::distance_t metric_t; + typedef nanoflann::KDTreeSingleIndexAdaptor< metric_t,self_t,DIM,IndexType> index_t; + + index_t* index; //! The kd-tree index for the user to call its methods as usual with any other FLANN index. + + /// Constructor: takes a const ref to the vector of vectors object with the data points + KDTreeVectorOfVectorsAdaptor(const size_t /* dimensionality */, const VectorOfVectorsType &mat, const int leaf_max_size = 10) : m_data(mat) + { + assert(mat.size() != 0 && mat[0].size() != 0); + const size_t dims = mat[0].size(); + if (DIM>0 && static_cast(dims) != DIM) + throw std::runtime_error("Data set dimensionality does not match the 'DIM' template argument"); + index = new index_t( static_cast(dims), *this /* adaptor */, nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size ) ); + index->buildIndex(); + } + + ~KDTreeVectorOfVectorsAdaptor() { + delete index; + } + + const VectorOfVectorsType &m_data; + + /** Query for the \a num_closest closest points to a given point (entered as query_point[0:dim-1]). + * Note that this is a short-cut method for index->findNeighbors(). + * The user can also call index->... methods as desired. + * \note nChecks_IGNORED is ignored but kept for compatibility with the original FLANN interface. + */ + inline void query(const num_t *query_point, const size_t num_closest, IndexType *out_indices, num_t *out_distances_sq, const int nChecks_IGNORED = 10) const + { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + index->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + } + + /** @name Interface expected by KDTreeSingleIndexAdaptor + * @{ */ + + const self_t & derived() const { + return *this; + } + self_t & derived() { + return *this; + } + + // Must return the number of data points + inline size_t kdtree_get_point_count() const { + return m_data.size(); + } + + // Returns the dim'th component of the idx'th point in the class: + inline num_t kdtree_get_pt(const size_t idx, const size_t dim) const { + return m_data[idx][dim]; + } + + // Optional bounding-box computation: return false to default to a standard bbox computation loop. + // Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again. + // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds) + template + bool kdtree_get_bbox(BBOX & /*bb*/) const { + return false; + } + + /** @} */ + +}; // end of KDTreeVectorOfVectorsAdaptor diff --git a/include/apriltag_utils.h b/include/apriltag_utils.h index 2651857..08e8d66 100644 --- a/include/apriltag_utils.h +++ b/include/apriltag_utils.h @@ -31,7 +31,7 @@ #ifndef APRILTAG_UTILS_H #define APRILTAG_UTILS_H -#include "lidar_tag.h" +#include "lidartag.h" namespace BipedAprilLab{ diff --git a/include/lidar_tag.h b/include/lidartag.h similarity index 52% rename from include/lidar_tag.h rename to include/lidartag.h index 5a44afd..96ece4b 100644 --- a/include/lidar_tag.h +++ b/include/lidartag.h @@ -36,6 +36,9 @@ #include // std::queue #include +#include +#include +#include #include #include @@ -44,7 +47,10 @@ #include // Marker #include // Marker + +// threadings #include +#include // To trasnform to pcl format #include @@ -53,14 +59,19 @@ #include #include #include +#include #include #include + #include "lidartag_msgs/LiDARTagDetection.h" #include "lidartag_msgs/LiDARTagDetectionArray.h" #include "types.h" +#include "thread_pool.h" +// #include "mat.h" +// #include "matrix.h" // #include "tensorflow_ros_test/lib.h" namespace BipedLab{ @@ -80,9 +91,23 @@ namespace BipedLab{ int _valgrind_check; // Debugging with Valgrind int _fake_tag; int _decode_method; // Which decode methods to use? + + + int _optimization_solver; + int _decode_mode; int _grid_viz; // visualize remapping grid + bool _mark_cluster_validity; + bool _plane_fitting; // whether perform plane fitting + bool _pose_optimization; // optimize pose or not bool _id_decoding; // decode id or not bool _write_CSV; // Write CSV files + bool _calibration; + bool _has_ring; // data has ring_num or not + bool _ring_estimation; // need to estimate ring_num or not + bool _ring_estimated; + bool _use_ring; // use ring information or not + int _num_accumulation; // Accumuate # of scans as a full scan of lidar + int _iter; //iterations of frame std::string _assign_id; // Directly assign Id, mainly for calibration usage // ROS @@ -90,15 +115,31 @@ namespace BipedLab{ ros::Subscriber _LiDAR1_sub; ros::Publisher _original_pc_pub; ros::Publisher _edge_pub; + ros::Publisher _transformed_points_pub; + ros::Publisher _transformed_points_tag_pub; + ros::Publisher _edge1_pub; + ros::Publisher _edge2_pub; + ros::Publisher _edge3_pub; + ros::Publisher _edge4_pub; + ros::Publisher _boundary_pub; ros::Publisher _cluster_pub; ros::Publisher _payload_pub; - + ros::Publisher _payload3d_pub; + ros::Publisher _tag_pub; + ros::Publisher _ini_tag_pub; + // ros::Publisher _index_pub; ros::Publisher _cluster_marker_pub; // cluster markers ros::Publisher _boundary_marker_pub; // cluster boundary + ros::Publisher _id_marker_pub; ros::Publisher _payload_marker_pub; // payload boundary ros::Publisher _payload_grid_pub; // grid visualization ros::Publisher _payload_grid_line_pub; // grid visualization + ros::Publisher _ideal_frame_pub; + ros::Publisher _tag_frame_pub; + ros::Publisher _edge_vector_pub; ros::Publisher _lidartag_pose_pub; // Publish LiDAR pose + ros::Publisher _clustered_points_pub; // Points after minor clusters removed + ros::Publisher _detectionArray_pub; // Flag int _point_cloud_received; // check if a scan of point cloud has received or not @@ -112,24 +153,19 @@ namespace BipedLab{ //ros::Publisher TextPub_; // publish text // visualization_msgs::MarkerArray _markers; - // Queue for pc data std::queue _point_cloud1_queue; - // lock - boost::mutex _refine_lock; - boost::mutex _buff_to_pcl_vector_lock; - boost::mutex _point_cloud1_queue_lock; // LiDAR parameters ros::Time _current_scan_time; // store current time of the lidar scan std::string _pointcloud_topic; // subscribe channel std::string _pub_frame; // publish under what frame? - + std::string lidartag_detection_topic; // Overall LiDAR system parameters LiDARSystem_t _LiDAR_system; int _beam_num; - int _vertical_fov; + double _vertical_fov; // PointCould data (for a single scan) int _point_cloud_size; @@ -141,6 +177,7 @@ namespace BipedLab{ // If on-board processing is limited, limit range of points double _distance_bound; + double _distance_threshold; // fiducial marker parameters double _payload_size; // physical payload size @@ -148,21 +185,59 @@ namespace BipedLab{ int _tag_hamming_distance; // what tag family ie tag16h5, this should be 5 int _max_decode_hamming; // max hamming while decoding int _black_border; // black boarder of the fiducial marker + int _num_codes; + int _num_tag_sizes; + std::vector> _function_dic; + std::vector> _function_dic_xyz; // for kd tree + std::vector> _function_dic_feat; // for kdtree + std::vector> _rkhs_function_name_list; // Cluster parameters - double _threshold; + double _linkage_threshold; double _RANSAC_threshold; int _fine_cluster_threshold; // TODO: REPLACE WITH TAG PARAMETERS int _filling_gap_max_index; // TODO: CHECK int _filling_max_points_threshold; //TODO: REMOVE double _points_threshold_factor; // TODO: CHECK - + double _distance_to_plane_threshold; + double _max_outlier_ratio; + int _num_points_for_plane_feature; + double _nearby_factor; + int _minimum_ring_boundary_points; + int _np_ring; + double _linkage_tunable; + std::vector _tag_size_list; + double _optimization_percent; + + bool _print_ros_info; + bool _debug_info; + bool _debug_time; + bool _debug_decoding_time; + bool _log_data; + bool _derivative_method; // Payload double _line_intensity_bound; // TODO: not sure but may okay to remove it for releasing double _payload_intensity_threshold; + double _opt_lb; + double _opt_ub; + double _coa_tunable; + double _tagsize_tunable; int _min_returns_per_grid; GrizTagFamily_t *tf; lidartag_msgs::LiDARTagDetectionArray _lidartag_pose_array; // an array of apriltags + lidartag_msgs::LiDARTagDetectionArray detectionsToPub; + + + + // threadings + int _num_threads; + std::shared_ptr _thread_vec; + + + // lock + boost::mutex _refine_lock; + boost::mutex _buff_to_pcl_vector_lock; + boost::mutex _point_cloud1_queue_lock; // NN @@ -175,10 +250,15 @@ namespace BipedLab{ // Debug Debug_t _debug_cluster; Timing_t _timing; + TimeDecoding_t _time_decoding; // Statistics Statistics_t _result_statistics; - + std::string _stats_file_path; + std::string _cluster_file_path; + std::string _pose_file_path; + std::string _outputs_path; + std::string _library_path; /***************************************************** * Functions @@ -220,11 +300,12 @@ namespace BipedLab{ /* [Transform/Publish] * A function to transform pcl msgs to ros msgs and then publish - * WhichPublisher should be a string of "organized" or "original" regardless - * lowercase and uppercase + * WhichPublisher should be a string of "organized" or "original" + * regardless lowercase and uppercase */ - void _publishPC(const pcl::PointCloud::Ptr &t_source_PC, - const std::string &t_frame_name, std::string t_which_publisher); + void _publishPC(const pcl::PointCloud::Ptr &t_source_PC, + const std::string &t_frame_name, + std::string t_which_publisher); /* [Type transformation] * A function to transform from a customized type (LiDARpoints_t) of vector of @@ -239,8 +320,15 @@ namespace BipedLab{ */ inline void _fillInOrderedPC(const pcl::PointCloud::Ptr &t_pcl_pointcloud, std::vector< std::vector > &t_ordered_buff); - - + /* + * A function to compute angle between the line from origin to this point + * and z=0 plane in lidar + * */ + float _getAnglefromPt(PointXYZRI &t_point); + + void _getAngleVector( + const pcl::PointCloud::Ptr &pcl_pointcloud, + std::vector &angles); /* [Type transformation] * A function to get pcl OrderedBuff from a ros sensor-msgs form of * pointcould queue @@ -299,6 +387,17 @@ namespace BipedLab{ std::vector> &t_edge_buff, std::vector &t_cluster_buff); + /* [Edge detection from n consecutive points] + * + * A function to + * (1) kick out points are not near to each other + * (2) find edge points from two side points of these points + * Return value : 0 mean no edge point, 1 mean the left side point is the edge point + * Return value : 2 mean the right side point is the edge point, 3 mean two side points are edge points + */ + int _getEdgePoints(const std::vector>& OrderedBuff, + int i, int j, int n); + /* [Clustering-Linkage] * A function to cluster a single edge point into a new cluster or an existing cluster @@ -315,7 +414,17 @@ namespace BipedLab{ ClusterFamily_t &t_old_cluster, TestCluster_t *t_new_cluster); + /* [Adaptive-Clustering] + * A function that determines if a point is within a given cluster adaptively + * based on the ring number and range of the point. + */ + bool _isWithinCluster(const LiDARPoints_t &point, ClusterFamily_t &cluster); + /* [Adaptive-Clustering] + * A function that determines if a point is within a given cluster horizontally and adaptively + * based on the range of the point. + */ + bool _isWithinClusterHorizon(const LiDARPoints_t &point, ClusterFamily_t &cluster, double threshold); /* [Clustering-Validation] * A function to @@ -371,21 +480,77 @@ namespace BipedLab{ */ void _extractPayloadWOThreshold(ClusterFamily_t &t_cluster); + /* + * A function to calculate the average point of valid edge points + */ + void _organizeDataPoints(ClusterFamily_t &t_cluster); + /* [Edge points and principal axes] + * A function to transform the edge points to the tag frame + */ + bool _transformSplitEdges(ClusterFamily_t &t_cluster); + /* + * A function to store transformed points + */ + void _storeTemplatePts(ClusterFamily_t &t_Cluster); + + + /* [Unordered corner points] + * A function to reorder the undered corner points from PCA + */ + Eigen::MatrixXf _getOrderedCorners(Eigen::MatrixXf &t_payload_vertices, ClusterFamily_t &t_Cluster); + + /* [two lines] + * A function to compute the intersection of two lines + */ + Eigen::Vector3f _getintersec(Eigen::Vector4f t_line1, Eigen::Vector4f t_line2); + + /* [four corner points] + * A function to compute tag size according to the corner points of the tag + */ + bool _estimateTargetSize( + ClusterFamily_t &t_cluster, + const Eigen::Vector3f &point1, + const Eigen::Vector3f &point2, + const Eigen::Vector3f &point3, + const Eigen::Vector3f &point4); + + /* [A set of 2D points] + * A function to transform the edge points to the tag frame + */ + bool _getLines(pcl::PointCloud::Ptr t_cloud, Eigen::Vector4f &t_line); /* [Type transformation] * A function to transform an eigen type of vector to pcl point type */ void _eigenVectorToPointXYZRI(const Eigen::Vector4f &t_vector, PointXYZRI &t_point); + /* [Type transformation] + * A function to transform a pcl point type to an eigen vector + */ + void _PointXYZRIToEigenVector(const PointXYZRI &point, Eigen::Vector4f &Vector); + /* [Normal vector] * A function to estimate the normal vector of a potential payload */ - Eigen::MatrixXf _estimateNormalVector(ClusterFamily_t &cluster); + //Eigen::MatrixXf + void _estimatePrincipleAxis(ClusterFamily_t &cluster); + /* [pose] + * A function to estimate the pose of a potential payload + */ + Homogeneous_t _estimatePose(ClusterFamily_t &cluster); + /*[oritented vector] + */ + Eigen::Vector3f _estimateEdgeVector(ClusterFamily_t &Cluster); + /* [pose] + * A function to optimize the pose of a potential payload with L1 optimization + */ + int _optimizePose(ClusterFamily_t &cluster); + bool _optimizePoseGrad(ClusterFamily_t &cluster); /* [Pose: tag to robot] * A function to publish pose of tag to the robot */ @@ -402,7 +567,7 @@ namespace BipedLab{ * 3: Gaussian Process * 4: ?! */ - bool _decodPayload(ClusterFamily_t &t_cluster); + bool _decodePayload(ClusterFamily_t &t_cluster); /* [Decoder] @@ -424,6 +589,186 @@ namespace BipedLab{ const pcl::PointCloud &t_payload, const std::vector &t_payload_boundary_ptr); + /* [Decoder] + * 1) Transfrom the payload points to 3D-shape pc + * 2) Compute inner product + * 3) + */ + int _getCodeRKHS(RKHSDecoding_t &rkhs_decoding, const double &tag_size); + + + Eigen::MatrixXf _construct3DShapeMarker(RKHSDecoding_t &rkhs_decoding, + const double &ell); + + float computeFunctionInnerProduct( + const Eigen::MatrixXf &pc1, + const Eigen::MatrixXf &pc2, + const float &ell); + + + void computeFunctionOriginalInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + + void computeFunctionMatrixInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + + void computeFunctionVectorInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void _assignClusterPose( + const Homogeneous_t &H_TL, + Homogeneous_t &H_LT, + const int &rotation_angle); + + + void singleTask(const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void singleTaskFixedSize( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + + void multipleTasks( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + + void computeFunctionVectorInnerProductThreading( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void test( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void computeFunctionVectorInnerProductTBBThreadingNoScheduling( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + void computeFunctionVectorInnerProductTBBThreadingManualScheduling( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void computeFunctionVectorInnerProductTBBThreadingTBBScheduling( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void computeFunctionOriginalInnerProductTBB( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void computeFunctionOriginalInnerProductKDTree( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + void computeFunctionInnerProductModes( + const int mode, + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score); + + + + + + + // Eigen::VectorXf d_px_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13); + // Eigen::VectorXf d_py_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13); + // Eigen::VectorXf d_pz_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13); + + /* [Decoder] * Create hash table of chosen tag family */ @@ -441,10 +786,34 @@ namespace BipedLab{ */ void _clusterToPclVectorAndMarkerPublisher(const std::vector &t_cluster, pcl::PointCloud::Ptr t_out_cluster, + pcl::PointCloud::Ptr t_out_edge_cluster, pcl::PointCloud::Ptr t_out_payload, + pcl::PointCloud::Ptr t_out_payload3d, + pcl::PointCloud::Ptr t_out_target, + pcl::PointCloud::Ptr t_ini_out_target, + pcl::PointCloud::Ptr t_edge1, + pcl::PointCloud::Ptr t_edge2, + pcl::PointCloud::Ptr t_edge3, + pcl::PointCloud::Ptr t_edge4, + pcl::PointCloud::Ptr t_boundary_pts, visualization_msgs::MarkerArray &t_marker_array); + void _plotIdealFrame(); + void _plotTagFrame(const ClusterFamily_t &t_cluster); + visualization_msgs::Marker _visualizeVector(Eigen::Vector3f edge_vector, PointXYZRI centriod, int t_ID); + /* [accumulating temporal cluster] + * A function to save temporal clusters data + */ + // void _saveTemporalCluster(const std::vector &t_cluster, std::vector>> &matData); + + /* [save points to mat files] + * A function to save points as .mat data + */ + // void _saveMatFiles(std::vector>>& matData); + + // [A function to put clusterFamily to LiDARTagDetectionArray] + void _detectionArrayPublisher(const ClusterFamily_t &Cluster); - + /* [Drawing] * A function to draw lines in rviz */ @@ -465,6 +834,30 @@ namespace BipedLab{ const PointXYZRI &t_point, const int t_count, const double t_size, const std::string Text=""); + void _assignVectorMarker(visualization_msgs::Marker &t_marker, const uint32_t t_shape, + const std::string t_namespace, + const double r, const double g, const double b, + const int t_count, const double t_size, Eigen::Vector3f t_edge_vector, const PointXYZRI &t_centriod, + const std::string Text=""); + + void _printStatistics( + const std::vector& ClusterBuff); + + std::vector _getValidClusters(const std::vector& ClusterBuff); + + void _maxPointsCheck(ClusterFamily_t& Cluster); + + bool _rejectWithPlanarCheck( ClusterFamily_t &Cluster, + pcl::PointIndices::Ptr inliers, pcl::ModelCoefficients::Ptr coefficients, + std::ostream &fplanefit); + + void _initFunctionDecoder(); + + + /// + // void _calculateCost(Eigen::Vector3f q, double & costx, double & costy, double & costz); + // double _checkCost(double point, double cons1, double cons2); + // double _costfunc(const std::vector &x, std::vector &grad, void *func_data); /***************************************************** * not used diff --git a/include/nanoflann.hpp b/include/nanoflann.hpp new file mode 100644 index 0000000..ba0309c --- /dev/null +++ b/include/nanoflann.hpp @@ -0,0 +1,2049 @@ +/*********************************************************************** + * Software License Agreement (BSD License) + * + * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved. + * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved. + * Copyright 2011-2016 Jose Luis Blanco (joseluisblancoc@gmail.com). + * All rights reserved. + * + * THE BSD LICENSE + * + * 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 AUTHOR ``AS IS'' AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES + * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, + * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY + * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *************************************************************************/ + +/** \mainpage nanoflann C++ API documentation + * nanoflann is a C++ header-only library for building KD-Trees, mostly + * optimized for 2D or 3D point clouds. + * + * nanoflann does not require compiling or installing, just an + * #include in your code. + * + * See: + * - C++ API organized by modules + * - Online README + * - Doxygen + * documentation + */ + +#ifndef NANOFLANN_HPP_ +#define NANOFLANN_HPP_ + +#include +#include +#include +#include // for abs() +#include // for fwrite() +#include // for abs() +#include +#include // std::reference_wrapper +#include +#include + +/** Library version: 0xMmP (M=Major,m=minor,P=patch) */ +#define NANOFLANN_VERSION 0x132 + +// Avoid conflicting declaration of min/max macros in windows headers +#if !defined(NOMINMAX) && \ + (defined(_WIN32) || defined(_WIN32_) || defined(WIN32) || defined(_WIN64)) +#define NOMINMAX +#ifdef max +#undef max +#undef min +#endif +#endif + +namespace nanoflann { +/** @addtogroup nanoflann_grp nanoflann C++ library for ANN + * @{ */ + +/** the PI constant (required to avoid MSVC missing symbols) */ +template T pi_const() { + return static_cast(3.14159265358979323846); +} + +/** + * Traits if object is resizable and assignable (typically has a resize | assign + * method) + */ +template struct has_resize : std::false_type {}; + +template +struct has_resize().resize(1), 0)> + : std::true_type {}; + +template struct has_assign : std::false_type {}; + +template +struct has_assign().assign(1, 0), 0)> + : std::true_type {}; + +/** + * Free function to resize a resizable object + */ +template +inline typename std::enable_if::value, void>::type +resize(Container &c, const size_t nElements) { + c.resize(nElements); +} + +/** + * Free function that has no effects on non resizable containers (e.g. + * std::array) It raises an exception if the expected size does not match + */ +template +inline typename std::enable_if::value, void>::type +resize(Container &c, const size_t nElements) { + if (nElements != c.size()) + throw std::logic_error("Try to change the size of a std::array."); +} + +/** + * Free function to assign to a container + */ +template +inline typename std::enable_if::value, void>::type +assign(Container &c, const size_t nElements, const T &value) { + c.assign(nElements, value); +} + +/** + * Free function to assign to a std::array + */ +template +inline typename std::enable_if::value, void>::type +assign(Container &c, const size_t nElements, const T &value) { + for (size_t i = 0; i < nElements; i++) + c[i] = value; +} + +/** @addtogroup result_sets_grp Result set classes + * @{ */ +template +class KNNResultSet { +public: + typedef _DistanceType DistanceType; + typedef _IndexType IndexType; + typedef _CountType CountType; + +private: + IndexType *indices; + DistanceType *dists; + CountType capacity; + CountType count; + +public: + inline KNNResultSet(CountType capacity_) + : indices(0), dists(0), capacity(capacity_), count(0) {} + + inline void init(IndexType *indices_, DistanceType *dists_) { + indices = indices_; + dists = dists_; + count = 0; + if (capacity) + dists[capacity - 1] = (std::numeric_limits::max)(); + } + + inline CountType size() const { return count; } + + inline bool full() const { return count == capacity; } + + /** + * Called during search to add an element matching the criteria. + * @return true if the search should be continued, false if the results are + * sufficient + */ + inline bool addPoint(DistanceType dist, IndexType index) { + CountType i; + for (i = count; i > 0; --i) { +#ifdef NANOFLANN_FIRST_MATCH // If defined and two points have the same + // distance, the one with the lowest-index will be + // returned first. + if ((dists[i - 1] > dist) || + ((dist == dists[i - 1]) && (indices[i - 1] > index))) { +#else + if (dists[i - 1] > dist) { +#endif + if (i < capacity) { + dists[i] = dists[i - 1]; + indices[i] = indices[i - 1]; + } + } else + break; + } + if (i < capacity) { + dists[i] = dist; + indices[i] = index; + } + if (count < capacity) + count++; + + // tell caller that the search shall continue + return true; + } + + inline DistanceType worstDist() const { return dists[capacity - 1]; } +}; + +/** operator "<" for std::sort() */ +struct IndexDist_Sorter { + /** PairType will be typically: std::pair */ + template + inline bool operator()(const PairType &p1, const PairType &p2) const { + return p1.second < p2.second; + } +}; + +/** + * A result-set class used when performing a radius based search. + */ +template +class RadiusResultSet { +public: + typedef _DistanceType DistanceType; + typedef _IndexType IndexType; + +public: + const DistanceType radius; + + std::vector> &m_indices_dists; + + inline RadiusResultSet( + DistanceType radius_, + std::vector> &indices_dists) + : radius(radius_), m_indices_dists(indices_dists) { + init(); + } + + inline void init() { clear(); } + inline void clear() { m_indices_dists.clear(); } + + inline size_t size() const { return m_indices_dists.size(); } + + inline bool full() const { return true; } + + /** + * Called during search to add an element matching the criteria. + * @return true if the search should be continued, false if the results are + * sufficient + */ + inline bool addPoint(DistanceType dist, IndexType index) { + if (dist < radius) + m_indices_dists.push_back(std::make_pair(index, dist)); + return true; + } + + inline DistanceType worstDist() const { return radius; } + + /** + * Find the worst result (furtherest neighbor) without copying or sorting + * Pre-conditions: size() > 0 + */ + std::pair worst_item() const { + if (m_indices_dists.empty()) + throw std::runtime_error("Cannot invoke RadiusResultSet::worst_item() on " + "an empty list of results."); + typedef + typename std::vector>::const_iterator + DistIt; + DistIt it = std::max_element(m_indices_dists.begin(), m_indices_dists.end(), + IndexDist_Sorter()); + return *it; + } +}; + +/** @} */ + +/** @addtogroup loadsave_grp Load/save auxiliary functions + * @{ */ +template +void save_value(FILE *stream, const T &value, size_t count = 1) { + fwrite(&value, sizeof(value), count, stream); +} + +template +void save_value(FILE *stream, const std::vector &value) { + size_t size = value.size(); + fwrite(&size, sizeof(size_t), 1, stream); + fwrite(&value[0], sizeof(T), size, stream); +} + +template +void load_value(FILE *stream, T &value, size_t count = 1) { + size_t read_cnt = fread(&value, sizeof(value), count, stream); + if (read_cnt != count) { + throw std::runtime_error("Cannot read from file"); + } +} + +template void load_value(FILE *stream, std::vector &value) { + size_t size; + size_t read_cnt = fread(&size, sizeof(size_t), 1, stream); + if (read_cnt != 1) { + throw std::runtime_error("Cannot read from file"); + } + value.resize(size); + read_cnt = fread(&value[0], sizeof(T), size, stream); + if (read_cnt != size) { + throw std::runtime_error("Cannot read from file"); + } +} +/** @} */ + +/** @addtogroup metric_grp Metric (distance) classes + * @{ */ + +struct Metric {}; + +/** Manhattan distance functor (generic version, optimized for + * high-dimensionality data sets). Corresponding distance traits: + * nanoflann::metric_L1 \tparam T Type of the elements (e.g. double, float, + * uint8_t) \tparam _DistanceType Type of distance variables (must be signed) + * (e.g. float, double, int64_t) + */ +template +struct L1_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L1_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, + DistanceType worst_dist = -1) const { + DistanceType result = DistanceType(); + const T *last = a + size; + const T *lastgroup = last - 3; + size_t d = 0; + + /* Process 4 items with each loop for efficiency. */ + while (a < lastgroup) { + const DistanceType diff0 = + std::abs(a[0] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff1 = + std::abs(a[1] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff2 = + std::abs(a[2] - data_source.kdtree_get_pt(b_idx, d++)); + const DistanceType diff3 = + std::abs(a[3] - data_source.kdtree_get_pt(b_idx, d++)); + result += diff0 + diff1 + diff2 + diff3; + a += 4; + if ((worst_dist > 0) && (result > worst_dist)) { + return result; + } + } + /* Process last 0-3 components. Not needed for standard vector lengths. */ + while (a < last) { + result += std::abs(*a++ - data_source.kdtree_get_pt(b_idx, d++)); + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return std::abs(a - b); + } +}; + +/** Squared Euclidean distance functor (generic version, optimized for + * high-dimensionality data sets). Corresponding distance traits: + * nanoflann::metric_L2 \tparam T Type of the elements (e.g. double, float, + * uint8_t) \tparam _DistanceType Type of distance variables (must be signed) + * (e.g. float, double, int64_t) + */ +template +struct L2_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, + DistanceType worst_dist = -1) const { + DistanceType result = DistanceType(); + const T *last = a + size; + const T *lastgroup = last - 3; + size_t d = 0; + + /* Process 4 items with each loop for efficiency. */ + while (a < lastgroup) { + const DistanceType diff0 = a[0] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff1 = a[1] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff2 = a[2] - data_source.kdtree_get_pt(b_idx, d++); + const DistanceType diff3 = a[3] - data_source.kdtree_get_pt(b_idx, d++); + result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3; + a += 4; + if ((worst_dist > 0) && (result > worst_dist)) { + return result; + } + } + /* Process last 0-3 components. Not needed for standard vector lengths. */ + while (a < last) { + const DistanceType diff0 = *a++ - data_source.kdtree_get_pt(b_idx, d++); + result += diff0 * diff0; + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return (a - b) * (a - b); + } +}; + +/** Squared Euclidean (L2) distance functor (suitable for low-dimensionality + * datasets, like 2D or 3D point clouds) Corresponding distance traits: + * nanoflann::metric_L2_Simple \tparam T Type of the elements (e.g. double, + * float, uint8_t) \tparam _DistanceType Type of distance variables (must be + * signed) (e.g. float, double, int64_t) + */ +template +struct L2_Simple_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + L2_Simple_Adaptor(const DataSource &_data_source) + : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + DistanceType result = DistanceType(); + for (size_t i = 0; i < size; ++i) { + const DistanceType diff = a[i] - data_source.kdtree_get_pt(b_idx, i); + result += diff * diff; + } + return result; + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + return (a - b) * (a - b); + } +}; + +/** SO2 distance functor + * Corresponding distance traits: nanoflann::metric_SO2 + * \tparam T Type of the elements (e.g. double, float) + * \tparam _DistanceType Type of distance variables (must be signed) (e.g. + * float, double) orientation is constrained to be in [-pi, pi] + */ +template +struct SO2_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + const DataSource &data_source; + + SO2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + return accum_dist(a[size - 1], data_source.kdtree_get_pt(b_idx, size - 1), + size - 1); + } + + /** Note: this assumes that input angles are already in the range [-pi,pi] */ + template + inline DistanceType accum_dist(const U a, const V b, const size_t) const { + DistanceType result = DistanceType(); + DistanceType PI = pi_const(); + result = b - a; + if (result > PI) + result -= 2 * PI; + else if (result < -PI) + result += 2 * PI; + return result; + } +}; + +/** SO3 distance functor (Uses L2_Simple) + * Corresponding distance traits: nanoflann::metric_SO3 + * \tparam T Type of the elements (e.g. double, float) + * \tparam _DistanceType Type of distance variables (must be signed) (e.g. + * float, double) + */ +template +struct SO3_Adaptor { + typedef T ElementType; + typedef _DistanceType DistanceType; + + L2_Simple_Adaptor distance_L2_Simple; + + SO3_Adaptor(const DataSource &_data_source) + : distance_L2_Simple(_data_source) {} + + inline DistanceType evalMetric(const T *a, const size_t b_idx, + size_t size) const { + return distance_L2_Simple.evalMetric(a, b_idx, size); + } + + template + inline DistanceType accum_dist(const U a, const V b, const size_t idx) const { + return distance_L2_Simple.accum_dist(a, b, idx); + } +}; + +/** Metaprogramming helper traits class for the L1 (Manhattan) metric */ +struct metric_L1 : public Metric { + template struct traits { + typedef L1_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the L2 (Euclidean) metric */ +struct metric_L2 : public Metric { + template struct traits { + typedef L2_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the L2_simple (Euclidean) metric */ +struct metric_L2_Simple : public Metric { + template struct traits { + typedef L2_Simple_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */ +struct metric_SO2 : public Metric { + template struct traits { + typedef SO2_Adaptor distance_t; + }; +}; +/** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */ +struct metric_SO3 : public Metric { + template struct traits { + typedef SO3_Adaptor distance_t; + }; +}; + +/** @} */ + +/** @addtogroup param_grp Parameter structs + * @{ */ + +/** Parameters (see README.md) */ +struct KDTreeSingleIndexAdaptorParams { + KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size = 10) + : leaf_max_size(_leaf_max_size) {} + + size_t leaf_max_size; +}; + +/** Search options for KDTreeSingleIndexAdaptor::findNeighbors() */ +struct SearchParams { + /** Note: The first argument (checks_IGNORED_) is ignored, but kept for + * compatibility with the FLANN interface */ + SearchParams(int checks_IGNORED_ = 32, float eps_ = 0, bool sorted_ = true) + : checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {} + + int checks; //!< Ignored parameter (Kept for compatibility with the FLANN + //!< interface). + float eps; //!< search for eps-approximate neighbours (default: 0) + bool sorted; //!< only for radius search, require neighbours sorted by + //!< distance (default: true) +}; +/** @} */ + +/** @addtogroup memalloc_grp Memory allocation + * @{ */ + +/** + * Allocates (using C's malloc) a generic type T. + * + * Params: + * count = number of instances to allocate. + * Returns: pointer (of type T*) to memory buffer + */ +template inline T *allocate(size_t count = 1) { + T *mem = static_cast(::malloc(sizeof(T) * count)); + return mem; +} + +/** + * Pooled storage allocator + * + * The following routines allow for the efficient allocation of storage in + * small chunks from a specified pool. Rather than allowing each structure + * to be freed individually, an entire pool of storage is freed at once. + * This method has two advantages over just using malloc() and free(). First, + * it is far more efficient for allocating small objects, as there is + * no overhead for remembering all the information needed to free each + * object or consolidating fragmented memory. Second, the decision about + * how long to keep an object is made at the time of allocation, and there + * is no need to track down all the objects to free them. + * + */ + +const size_t WORDSIZE = 16; +const size_t BLOCKSIZE = 8192; + +class PooledAllocator { + /* We maintain memory alignment to word boundaries by requiring that all + allocations be in multiples of the machine wordsize. */ + /* Size of machine word in bytes. Must be power of 2. */ + /* Minimum number of bytes requested at a time from the system. Must be + * multiple of WORDSIZE. */ + + size_t remaining; /* Number of bytes left in current block of storage. */ + void *base; /* Pointer to base of current block of storage. */ + void *loc; /* Current location in block to next allocate memory. */ + + void internal_init() { + remaining = 0; + base = NULL; + usedMemory = 0; + wastedMemory = 0; + } + +public: + size_t usedMemory; + size_t wastedMemory; + + /** + Default constructor. Initializes a new pool. + */ + PooledAllocator() { internal_init(); } + + /** + * Destructor. Frees all the memory allocated in this pool. + */ + ~PooledAllocator() { free_all(); } + + /** Frees all allocated memory chunks */ + void free_all() { + while (base != NULL) { + void *prev = + *(static_cast(base)); /* Get pointer to prev block. */ + ::free(base); + base = prev; + } + internal_init(); + } + + /** + * Returns a pointer to a piece of new memory of the given size in bytes + * allocated from the pool. + */ + void *malloc(const size_t req_size) { + /* Round size up to a multiple of wordsize. The following expression + only works for WORDSIZE that is a power of 2, by masking last bits of + incremented size to zero. + */ + const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1); + + /* Check whether a new block must be allocated. Note that the first word + of a block is reserved for a pointer to the previous block. + */ + if (size > remaining) { + + wastedMemory += remaining; + + /* Allocate new storage. */ + const size_t blocksize = + (size + sizeof(void *) + (WORDSIZE - 1) > BLOCKSIZE) + ? size + sizeof(void *) + (WORDSIZE - 1) + : BLOCKSIZE; + + // use the standard C malloc to allocate memory + void *m = ::malloc(blocksize); + if (!m) { + fprintf(stderr, "Failed to allocate memory.\n"); + throw std::bad_alloc(); + } + + /* Fill first word of new block with pointer to previous block. */ + static_cast(m)[0] = base; + base = m; + + size_t shift = 0; + // int size_t = (WORDSIZE - ( (((size_t)m) + sizeof(void*)) & + // (WORDSIZE-1))) & (WORDSIZE-1); + + remaining = blocksize - sizeof(void *) - shift; + loc = (static_cast(m) + sizeof(void *) + shift); + } + void *rloc = loc; + loc = static_cast(loc) + size; + remaining -= size; + + usedMemory += size; + + return rloc; + } + + /** + * Allocates (using this pool) a generic type T. + * + * Params: + * count = number of instances to allocate. + * Returns: pointer (of type T*) to memory buffer + */ + template T *allocate(const size_t count = 1) { + T *mem = static_cast(this->malloc(sizeof(T) * count)); + return mem; + } +}; +/** @} */ + +/** @addtogroup nanoflann_metaprog_grp Auxiliary metaprogramming stuff + * @{ */ + +/** Used to declare fixed-size arrays when DIM>0, dynamically-allocated vectors + * when DIM=-1. Fixed size version for a generic DIM: + */ +template struct array_or_vector_selector { + typedef std::array container_t; +}; +/** Dynamic size version */ +template struct array_or_vector_selector<-1, T> { + typedef std::vector container_t; +}; + +/** @} */ + +/** kd-tree base-class + * + * Contains the member functions common to the classes KDTreeSingleIndexAdaptor + * and KDTreeSingleIndexDynamicAdaptor_. + * + * \tparam Derived The name of the class which inherits this class. + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use, these are all classes derived + * from nanoflann::Metric \tparam DIM Dimensionality of data points (e.g. 3 for + * 3D points) \tparam IndexType Will be typically size_t or int + */ + +template +class KDTreeBaseClass { + +public: + /** Frees the previously-built index. Automatically called within + * buildIndex(). */ + void freeIndex(Derived &obj) { + obj.pool.free_all(); + obj.root_node = NULL; + obj.m_size_at_index_build = 0; + } + + typedef typename Distance::ElementType ElementType; + typedef typename Distance::DistanceType DistanceType; + + /*--------------------- Internal Data Structures --------------------------*/ + struct Node { + /** Union used because a node can be either a LEAF node or a non-leaf node, + * so both data fields are never used simultaneously */ + union { + struct leaf { + IndexType left, right; //!< Indices of points in leaf node + } lr; + struct nonleaf { + int divfeat; //!< Dimension used for subdivision. + DistanceType divlow, divhigh; //!< The values used for subdivision. + } sub; + } node_type; + Node *child1, *child2; //!< Child nodes (both=NULL mean its a leaf node) + }; + + typedef Node *NodePtr; + + struct Interval { + ElementType low, high; + }; + + /** + * Array of indices to vectors in the dataset. + */ + std::vector vind; + + NodePtr root_node; + + size_t m_leaf_max_size; + + size_t m_size; //!< Number of current points in the dataset + size_t m_size_at_index_build; //!< Number of points in the dataset when the + //!< index was built + int dim; //!< Dimensionality of each data point + + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef + typename array_or_vector_selector::container_t BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename array_or_vector_selector::container_t + distance_vector_t; + + /** The KD-tree used to find neighbours */ + + BoundingBox root_bbox; + + /** + * Pooled memory allocator. + * + * Using a pooled memory allocator is more efficient + * than allocating memory directly when there is a large + * number small of memory allocations. + */ + PooledAllocator pool; + + /** Returns number of points in dataset */ + size_t size(const Derived &obj) const { return obj.m_size; } + + /** Returns the length of each point in the dataset */ + size_t veclen(const Derived &obj) { + return static_cast(DIM > 0 ? DIM : obj.dim); + } + + /// Helper accessor to the dataset points: + inline ElementType dataset_get(const Derived &obj, size_t idx, + int component) const { + return obj.dataset.kdtree_get_pt(idx, component); + } + + /** + * Computes the inde memory usage + * Returns: memory used by the index + */ + size_t usedMemory(Derived &obj) { + return obj.pool.usedMemory + obj.pool.wastedMemory + + obj.dataset.kdtree_get_point_count() * + sizeof(IndexType); // pool memory and vind array memory + } + + void computeMinMax(const Derived &obj, IndexType *ind, IndexType count, + int element, ElementType &min_elem, + ElementType &max_elem) { + min_elem = dataset_get(obj, ind[0], element); + max_elem = dataset_get(obj, ind[0], element); + for (IndexType i = 1; i < count; ++i) { + ElementType val = dataset_get(obj, ind[i], element); + if (val < min_elem) + min_elem = val; + if (val > max_elem) + max_elem = val; + } + } + + /** + * Create a tree node that subdivides the list of vecs from vind[first] + * to vind[last]. The routine is called recursively on each sublist. + * + * @param left index of the first vector + * @param right index of the last vector + */ + NodePtr divideTree(Derived &obj, const IndexType left, const IndexType right, + BoundingBox &bbox) { + NodePtr node = obj.pool.template allocate(); // allocate memory + + /* If too few exemplars remain, then make this a leaf node. */ + if ((right - left) <= static_cast(obj.m_leaf_max_size)) { + node->child1 = node->child2 = NULL; /* Mark as leaf node. */ + node->node_type.lr.left = left; + node->node_type.lr.right = right; + + // compute bounding-box of leaf points + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + bbox[i].low = dataset_get(obj, obj.vind[left], i); + bbox[i].high = dataset_get(obj, obj.vind[left], i); + } + for (IndexType k = left + 1; k < right; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + if (bbox[i].low > dataset_get(obj, obj.vind[k], i)) + bbox[i].low = dataset_get(obj, obj.vind[k], i); + if (bbox[i].high < dataset_get(obj, obj.vind[k], i)) + bbox[i].high = dataset_get(obj, obj.vind[k], i); + } + } + } else { + IndexType idx; + int cutfeat; + DistanceType cutval; + middleSplit_(obj, &obj.vind[0] + left, right - left, idx, cutfeat, cutval, + bbox); + + node->node_type.sub.divfeat = cutfeat; + + BoundingBox left_bbox(bbox); + left_bbox[cutfeat].high = cutval; + node->child1 = divideTree(obj, left, left + idx, left_bbox); + + BoundingBox right_bbox(bbox); + right_bbox[cutfeat].low = cutval; + node->child2 = divideTree(obj, left + idx, right, right_bbox); + + node->node_type.sub.divlow = left_bbox[cutfeat].high; + node->node_type.sub.divhigh = right_bbox[cutfeat].low; + + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low); + bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high); + } + } + + return node; + } + + void middleSplit_(Derived &obj, IndexType *ind, IndexType count, + IndexType &index, int &cutfeat, DistanceType &cutval, + const BoundingBox &bbox) { + const DistanceType EPS = static_cast(0.00001); + ElementType max_span = bbox[0].high - bbox[0].low; + for (int i = 1; i < (DIM > 0 ? DIM : obj.dim); ++i) { + ElementType span = bbox[i].high - bbox[i].low; + if (span > max_span) { + max_span = span; + } + } + ElementType max_spread = -1; + cutfeat = 0; + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + ElementType span = bbox[i].high - bbox[i].low; + if (span > (1 - EPS) * max_span) { + ElementType min_elem, max_elem; + computeMinMax(obj, ind, count, i, min_elem, max_elem); + ElementType spread = max_elem - min_elem; + ; + if (spread > max_spread) { + cutfeat = i; + max_spread = spread; + } + } + } + // split in the middle + DistanceType split_val = (bbox[cutfeat].low + bbox[cutfeat].high) / 2; + ElementType min_elem, max_elem; + computeMinMax(obj, ind, count, cutfeat, min_elem, max_elem); + + if (split_val < min_elem) + cutval = min_elem; + else if (split_val > max_elem) + cutval = max_elem; + else + cutval = split_val; + + IndexType lim1, lim2; + planeSplit(obj, ind, count, cutfeat, cutval, lim1, lim2); + + if (lim1 > count / 2) + index = lim1; + else if (lim2 < count / 2) + index = lim2; + else + index = count / 2; + } + + /** + * Subdivide the list of points by a plane perpendicular on axe corresponding + * to the 'cutfeat' dimension at 'cutval' position. + * + * On return: + * dataset[ind[0..lim1-1]][cutfeat]cutval + */ + void planeSplit(Derived &obj, IndexType *ind, const IndexType count, + int cutfeat, DistanceType &cutval, IndexType &lim1, + IndexType &lim2) { + /* Move vector indices for left subtree to front of list. */ + IndexType left = 0; + IndexType right = count - 1; + for (;;) { + while (left <= right && dataset_get(obj, ind[left], cutfeat) < cutval) + ++left; + while (right && left <= right && + dataset_get(obj, ind[right], cutfeat) >= cutval) + --right; + if (left > right || !right) + break; // "!right" was added to support unsigned Index types + std::swap(ind[left], ind[right]); + ++left; + --right; + } + /* If either list is empty, it means that all remaining features + * are identical. Split in the middle to maintain a balanced tree. + */ + lim1 = left; + right = count - 1; + for (;;) { + while (left <= right && dataset_get(obj, ind[left], cutfeat) <= cutval) + ++left; + while (right && left <= right && + dataset_get(obj, ind[right], cutfeat) > cutval) + --right; + if (left > right || !right) + break; // "!right" was added to support unsigned Index types + std::swap(ind[left], ind[right]); + ++left; + --right; + } + lim2 = left; + } + + DistanceType computeInitialDistances(const Derived &obj, + const ElementType *vec, + distance_vector_t &dists) const { + assert(vec); + DistanceType distsq = DistanceType(); + + for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) { + if (vec[i] < obj.root_bbox[i].low) { + dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].low, i); + distsq += dists[i]; + } + if (vec[i] > obj.root_bbox[i].high) { + dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].high, i); + distsq += dists[i]; + } + } + return distsq; + } + + void save_tree(Derived &obj, FILE *stream, NodePtr tree) { + save_value(stream, *tree); + if (tree->child1 != NULL) { + save_tree(obj, stream, tree->child1); + } + if (tree->child2 != NULL) { + save_tree(obj, stream, tree->child2); + } + } + + void load_tree(Derived &obj, FILE *stream, NodePtr &tree) { + tree = obj.pool.template allocate(); + load_value(stream, *tree); + if (tree->child1 != NULL) { + load_tree(obj, stream, tree->child1); + } + if (tree->child2 != NULL) { + load_tree(obj, stream, tree->child2); + } + } + + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex_(Derived &obj, FILE *stream) { + save_value(stream, obj.m_size); + save_value(stream, obj.dim); + save_value(stream, obj.root_bbox); + save_value(stream, obj.m_leaf_max_size); + save_value(stream, obj.vind); + save_tree(obj, stream, obj.root_node); + } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex_(Derived &obj, FILE *stream) { + load_value(stream, obj.m_size); + load_value(stream, obj.dim); + load_value(stream, obj.root_bbox); + load_value(stream, obj.m_leaf_max_size); + load_value(stream, obj.vind); + load_tree(obj, stream, obj.root_node); + } +}; + +/** @addtogroup kdtrees_grp KD-tree classes and adaptors + * @{ */ + +/** kd-tree static index + * + * Contains the k-d trees and other information for indexing a set of points + * for nearest-neighbor matching. + * + * The class "DatasetAdaptor" must provide the following interface (can be + * non-virtual, inlined methods): + * + * \code + * // Must return the number of data poins + * inline size_t kdtree_get_point_count() const { ... } + * + * + * // Must return the dim'th component of the idx'th point in the class: + * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... } + * + * // Optional bounding-box computation: return false to default to a standard + * bbox computation loop. + * // Return true if the BBOX was already computed by the class and returned + * in "bb" so it can be avoided to redo it again. + * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 + * for point clouds) template bool kdtree_get_bbox(BBOX &bb) const + * { + * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits + * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits + * ... + * return true; + * } + * + * \endcode + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexAdaptor + : public KDTreeBaseClass< + KDTreeSingleIndexAdaptor, + Distance, DatasetAdaptor, DIM, IndexType> { +public: + /** Deleted copy constructor*/ + KDTreeSingleIndexAdaptor( + const KDTreeSingleIndexAdaptor + &) = delete; + + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + const KDTreeSingleIndexAdaptorParams index_params; + + Distance distance; + + typedef typename nanoflann::KDTreeBaseClass< + nanoflann::KDTreeSingleIndexAdaptor, + Distance, DatasetAdaptor, DIM, IndexType> + BaseClassRef; + + typedef typename BaseClassRef::ElementType ElementType; + typedef typename BaseClassRef::DistanceType DistanceType; + + typedef typename BaseClassRef::Node Node; + typedef Node *NodePtr; + + typedef typename BaseClassRef::Interval Interval; + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef typename BaseClassRef::BoundingBox BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename BaseClassRef::distance_vector_t distance_vector_t; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexAdaptor(const int dimensionality, + const DatasetAdaptor &inputData, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams()) + : dataset(inputData), index_params(params), distance(inputData) { + BaseClassRef::root_node = NULL; + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + BaseClassRef::dim = dimensionality; + if (DIM > 0) + BaseClassRef::dim = DIM; + BaseClassRef::m_leaf_max_size = params.leaf_max_size; + + // Create a permutable array of indices to the input vectors. + init_vind(); + } + + /** + * Builds the index + */ + void buildIndex() { + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + init_vind(); + this->freeIndex(*this); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + if (BaseClassRef::m_size == 0) + return; + computeBoundingBox(BaseClassRef::root_bbox); + BaseClassRef::root_node = + this->divideTree(*this, 0, BaseClassRef::m_size, + BaseClassRef::root_bbox); // construct the tree + } + + /** \name Query methods + * @{ */ + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + assert(vec); + if (this->size(*this) == 0) + return false; + if (!BaseClassRef::root_node) + throw std::runtime_error( + "[nanoflann] findNeighbors() called before building the index."); + float epsError = 1 + searchParams.eps; + + distance_vector_t + dists; // fixed or variable-sized container (depending on DIM) + auto zero = static_cast(0); + assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim), + zero); // Fill it with zeros. + DistanceType distsq = this->computeInitialDistances(*this, vec, dists); + searchLevel(result, vec, BaseClassRef::root_node, distsq, dists, + epsError); // "count_leaf" parameter removed since was neither + // used nor returned to the user. + return result.full(); + } + + /** + * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1]. + * Their indices are stored inside the result object. \sa radiusSearch, + * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility + * with the original FLANN interface. \return Number `N` of valid points in + * the result set. Only the first `N` entries in `out_indices` and + * `out_distances_sq` will be valid. Return may be less than `num_closest` + * only if the number of elements in the tree is less than `num_closest`. + */ + size_t knnSearch(const ElementType *query_point, const size_t num_closest, + IndexType *out_indices, DistanceType *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + this->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + return resultSet.size(); + } + + /** + * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius. + * The output is given as a vector of pairs, of which the first element is a + * point index and the second the corresponding distance. Previous contents of + * \a IndicesDists are cleared. + * + * If searchParams.sorted==true, the output list is sorted by ascending + * distances. + * + * For a better performance, it is advisable to do a .reserve() on the vector + * if you have any wild guess about the number of expected matches. + * + * \sa knnSearch, findNeighbors, radiusSearchCustomCallback + * \return The number of points within the given radius (i.e. indices.size() + * or dists.size() ) + */ + size_t + radiusSearch(const ElementType *query_point, const DistanceType &radius, + std::vector> &IndicesDists, + const SearchParams &searchParams) const { + RadiusResultSet resultSet(radius, IndicesDists); + const size_t nFound = + radiusSearchCustomCallback(query_point, resultSet, searchParams); + if (searchParams.sorted) + std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter()); + return nFound; + } + + /** + * Just like radiusSearch() but with a custom callback class for each point + * found in the radius of the query. See the source of RadiusResultSet<> as a + * start point for your own classes. \sa radiusSearch + */ + template + size_t radiusSearchCustomCallback( + const ElementType *query_point, SEARCH_CALLBACK &resultSet, + const SearchParams &searchParams = SearchParams()) const { + this->findNeighbors(resultSet, query_point, searchParams); + return resultSet.size(); + } + + /** @} */ + +public: + /** Make sure the auxiliary list \a vind has the same size than the current + * dataset, and re-generate if size has changed. */ + void init_vind() { + // Create a permutable array of indices to the input vectors. + BaseClassRef::m_size = dataset.kdtree_get_point_count(); + if (BaseClassRef::vind.size() != BaseClassRef::m_size) + BaseClassRef::vind.resize(BaseClassRef::m_size); + for (size_t i = 0; i < BaseClassRef::m_size; i++) + BaseClassRef::vind[i] = i; + } + + void computeBoundingBox(BoundingBox &bbox) { + resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dataset.kdtree_get_bbox(bbox)) { + // Done! It was implemented in derived class + } else { + const size_t N = dataset.kdtree_get_point_count(); + if (!N) + throw std::runtime_error("[nanoflann] computeBoundingBox() called but " + "no data points found."); + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + bbox[i].low = bbox[i].high = this->dataset_get(*this, 0, i); + } + for (size_t k = 1; k < N; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + if (this->dataset_get(*this, k, i) < bbox[i].low) + bbox[i].low = this->dataset_get(*this, k, i); + if (this->dataset_get(*this, k, i) > bbox[i].high) + bbox[i].high = this->dataset_get(*this, k, i); + } + } + } + } + + /** + * Performs an exact search in the tree starting from a node. + * \tparam RESULTSET Should be any ResultSet + * \return true if the search should be continued, false if the results are + * sufficient + */ + template + bool searchLevel(RESULTSET &result_set, const ElementType *vec, + const NodePtr node, DistanceType mindistsq, + distance_vector_t &dists, const float epsError) const { + /* If this is a leaf node, then do check and return. */ + if ((node->child1 == NULL) && (node->child2 == NULL)) { + // count_leaf += (node->lr.right-node->lr.left); // Removed since was + // neither used nor returned to the user. + DistanceType worst_dist = result_set.worstDist(); + for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right; + ++i) { + const IndexType index = BaseClassRef::vind[i]; // reorder... : i; + DistanceType dist = distance.evalMetric( + vec, index, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dist < worst_dist) { + if (!result_set.addPoint(dist, BaseClassRef::vind[i])) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + } + } + return true; + } + + /* Which child branch should be taken first? */ + int idx = node->node_type.sub.divfeat; + ElementType val = vec[idx]; + DistanceType diff1 = val - node->node_type.sub.divlow; + DistanceType diff2 = val - node->node_type.sub.divhigh; + + NodePtr bestChild; + NodePtr otherChild; + DistanceType cut_dist; + if ((diff1 + diff2) < 0) { + bestChild = node->child1; + otherChild = node->child2; + cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx); + } else { + bestChild = node->child2; + otherChild = node->child1; + cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx); + } + + /* Call recursively to search next level down. */ + if (!searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError)) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + + DistanceType dst = dists[idx]; + mindistsq = mindistsq + cut_dist - dst; + dists[idx] = cut_dist; + if (mindistsq * epsError <= result_set.worstDist()) { + if (!searchLevel(result_set, vec, otherChild, mindistsq, dists, + epsError)) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return false; + } + } + dists[idx] = dst; + return true; + } + +public: + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); } + +}; // class KDTree + +/** kd-tree dynamic index + * + * Contains the k-d trees and other information for indexing a set of points + * for nearest-neighbor matching. + * + * The class "DatasetAdaptor" must provide the following interface (can be + * non-virtual, inlined methods): + * + * \code + * // Must return the number of data poins + * inline size_t kdtree_get_point_count() const { ... } + * + * // Must return the dim'th component of the idx'th point in the class: + * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... } + * + * // Optional bounding-box computation: return false to default to a standard + * bbox computation loop. + * // Return true if the BBOX was already computed by the class and returned + * in "bb" so it can be avoided to redo it again. + * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 + * for point clouds) template bool kdtree_get_bbox(BBOX &bb) const + * { + * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits + * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits + * ... + * return true; + * } + * + * \endcode + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexDynamicAdaptor_ + : public KDTreeBaseClass, + Distance, DatasetAdaptor, DIM, IndexType> { +public: + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + KDTreeSingleIndexAdaptorParams index_params; + + std::vector &treeIndex; + + Distance distance; + + typedef typename nanoflann::KDTreeBaseClass< + nanoflann::KDTreeSingleIndexDynamicAdaptor_, + Distance, DatasetAdaptor, DIM, IndexType> + BaseClassRef; + + typedef typename BaseClassRef::ElementType ElementType; + typedef typename BaseClassRef::DistanceType DistanceType; + + typedef typename BaseClassRef::Node Node; + typedef Node *NodePtr; + + typedef typename BaseClassRef::Interval Interval; + /** Define "BoundingBox" as a fixed-size or variable-size container depending + * on "DIM" */ + typedef typename BaseClassRef::BoundingBox BoundingBox; + + /** Define "distance_vector_t" as a fixed-size or variable-size container + * depending on "DIM" */ + typedef typename BaseClassRef::distance_vector_t distance_vector_t; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexDynamicAdaptor_( + const int dimensionality, const DatasetAdaptor &inputData, + std::vector &treeIndex_, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams()) + : dataset(inputData), index_params(params), treeIndex(treeIndex_), + distance(inputData) { + BaseClassRef::root_node = NULL; + BaseClassRef::m_size = 0; + BaseClassRef::m_size_at_index_build = 0; + BaseClassRef::dim = dimensionality; + if (DIM > 0) + BaseClassRef::dim = DIM; + BaseClassRef::m_leaf_max_size = params.leaf_max_size; + } + + /** Assignment operator definiton */ + KDTreeSingleIndexDynamicAdaptor_ + operator=(const KDTreeSingleIndexDynamicAdaptor_ &rhs) { + KDTreeSingleIndexDynamicAdaptor_ tmp(rhs); + std::swap(BaseClassRef::vind, tmp.BaseClassRef::vind); + std::swap(BaseClassRef::m_leaf_max_size, tmp.BaseClassRef::m_leaf_max_size); + std::swap(index_params, tmp.index_params); + std::swap(treeIndex, tmp.treeIndex); + std::swap(BaseClassRef::m_size, tmp.BaseClassRef::m_size); + std::swap(BaseClassRef::m_size_at_index_build, + tmp.BaseClassRef::m_size_at_index_build); + std::swap(BaseClassRef::root_node, tmp.BaseClassRef::root_node); + std::swap(BaseClassRef::root_bbox, tmp.BaseClassRef::root_bbox); + std::swap(BaseClassRef::pool, tmp.BaseClassRef::pool); + return *this; + } + + /** + * Builds the index + */ + void buildIndex() { + BaseClassRef::m_size = BaseClassRef::vind.size(); + this->freeIndex(*this); + BaseClassRef::m_size_at_index_build = BaseClassRef::m_size; + if (BaseClassRef::m_size == 0) + return; + computeBoundingBox(BaseClassRef::root_bbox); + BaseClassRef::root_node = + this->divideTree(*this, 0, BaseClassRef::m_size, + BaseClassRef::root_bbox); // construct the tree + } + + /** \name Query methods + * @{ */ + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + assert(vec); + if (this->size(*this) == 0) + return false; + if (!BaseClassRef::root_node) + return false; + float epsError = 1 + searchParams.eps; + + // fixed or variable-sized container (depending on DIM) + distance_vector_t dists; + // Fill it with zeros. + assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim), + static_cast(0)); + DistanceType distsq = this->computeInitialDistances(*this, vec, dists); + searchLevel(result, vec, BaseClassRef::root_node, distsq, dists, + epsError); // "count_leaf" parameter removed since was neither + // used nor returned to the user. + return result.full(); + } + + /** + * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1]. + * Their indices are stored inside the result object. \sa radiusSearch, + * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility + * with the original FLANN interface. \return Number `N` of valid points in + * the result set. Only the first `N` entries in `out_indices` and + * `out_distances_sq` will be valid. Return may be less than `num_closest` + * only if the number of elements in the tree is less than `num_closest`. + */ + size_t knnSearch(const ElementType *query_point, const size_t num_closest, + IndexType *out_indices, DistanceType *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + this->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + return resultSet.size(); + } + + /** + * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius. + * The output is given as a vector of pairs, of which the first element is a + * point index and the second the corresponding distance. Previous contents of + * \a IndicesDists are cleared. + * + * If searchParams.sorted==true, the output list is sorted by ascending + * distances. + * + * For a better performance, it is advisable to do a .reserve() on the vector + * if you have any wild guess about the number of expected matches. + * + * \sa knnSearch, findNeighbors, radiusSearchCustomCallback + * \return The number of points within the given radius (i.e. indices.size() + * or dists.size() ) + */ + size_t + radiusSearch(const ElementType *query_point, const DistanceType &radius, + std::vector> &IndicesDists, + const SearchParams &searchParams) const { + RadiusResultSet resultSet(radius, IndicesDists); + const size_t nFound = + radiusSearchCustomCallback(query_point, resultSet, searchParams); + if (searchParams.sorted) + std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter()); + return nFound; + } + + /** + * Just like radiusSearch() but with a custom callback class for each point + * found in the radius of the query. See the source of RadiusResultSet<> as a + * start point for your own classes. \sa radiusSearch + */ + template + size_t radiusSearchCustomCallback( + const ElementType *query_point, SEARCH_CALLBACK &resultSet, + const SearchParams &searchParams = SearchParams()) const { + this->findNeighbors(resultSet, query_point, searchParams); + return resultSet.size(); + } + + /** @} */ + +public: + void computeBoundingBox(BoundingBox &bbox) { + resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim)); + + if (dataset.kdtree_get_bbox(bbox)) { + // Done! It was implemented in derived class + } else { + const size_t N = BaseClassRef::m_size; + if (!N) + throw std::runtime_error("[nanoflann] computeBoundingBox() called but " + "no data points found."); + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + bbox[i].low = bbox[i].high = + this->dataset_get(*this, BaseClassRef::vind[0], i); + } + for (size_t k = 1; k < N; ++k) { + for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) { + if (this->dataset_get(*this, BaseClassRef::vind[k], i) < bbox[i].low) + bbox[i].low = this->dataset_get(*this, BaseClassRef::vind[k], i); + if (this->dataset_get(*this, BaseClassRef::vind[k], i) > bbox[i].high) + bbox[i].high = this->dataset_get(*this, BaseClassRef::vind[k], i); + } + } + } + } + + /** + * Performs an exact search in the tree starting from a node. + * \tparam RESULTSET Should be any ResultSet + */ + template + void searchLevel(RESULTSET &result_set, const ElementType *vec, + const NodePtr node, DistanceType mindistsq, + distance_vector_t &dists, const float epsError) const { + /* If this is a leaf node, then do check and return. */ + if ((node->child1 == NULL) && (node->child2 == NULL)) { + // count_leaf += (node->lr.right-node->lr.left); // Removed since was + // neither used nor returned to the user. + DistanceType worst_dist = result_set.worstDist(); + for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right; + ++i) { + const IndexType index = BaseClassRef::vind[i]; // reorder... : i; + if (treeIndex[index] == -1) + continue; + DistanceType dist = distance.evalMetric( + vec, index, (DIM > 0 ? DIM : BaseClassRef::dim)); + if (dist < worst_dist) { + if (!result_set.addPoint( + static_cast(dist), + static_cast( + BaseClassRef::vind[i]))) { + // the resultset doesn't want to receive any more points, we're done + // searching! + return; // false; + } + } + } + return; + } + + /* Which child branch should be taken first? */ + int idx = node->node_type.sub.divfeat; + ElementType val = vec[idx]; + DistanceType diff1 = val - node->node_type.sub.divlow; + DistanceType diff2 = val - node->node_type.sub.divhigh; + + NodePtr bestChild; + NodePtr otherChild; + DistanceType cut_dist; + if ((diff1 + diff2) < 0) { + bestChild = node->child1; + otherChild = node->child2; + cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx); + } else { + bestChild = node->child2; + otherChild = node->child1; + cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx); + } + + /* Call recursively to search next level down. */ + searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError); + + DistanceType dst = dists[idx]; + mindistsq = mindistsq + cut_dist - dst; + dists[idx] = cut_dist; + if (mindistsq * epsError <= result_set.worstDist()) { + searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError); + } + dists[idx] = dst; + } + +public: + /** Stores the index in a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when + * loading the index object it must be constructed associated to the same + * source of data points used while building it. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); } + + /** Loads a previous index from a binary file. + * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the + * index object must be constructed associated to the same source of data + * points used while building the index. See the example: + * examples/saveload_example.cpp \sa loadIndex */ + void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); } +}; + +/** kd-tree dynaimic index + * + * class to create multiple static index and merge their results to behave as + * single dynamic index as proposed in Logarithmic Approach. + * + * Example of usage: + * examples/dynamic_pointcloud_example.cpp + * + * \tparam DatasetAdaptor The user-provided adaptor (see comments above). + * \tparam Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM + * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will + * be typically size_t or int + */ +template +class KDTreeSingleIndexDynamicAdaptor { +public: + typedef typename Distance::ElementType ElementType; + typedef typename Distance::DistanceType DistanceType; + +protected: + size_t m_leaf_max_size; + size_t treeCount; + size_t pointCount; + + /** + * The dataset used by this index + */ + const DatasetAdaptor &dataset; //!< The source of our data + + std::vector treeIndex; //!< treeIndex[idx] is the index of tree in which + //!< point at idx is stored. treeIndex[idx]=-1 + //!< means that point has been removed. + + KDTreeSingleIndexAdaptorParams index_params; + + int dim; //!< Dimensionality of each data point + + typedef KDTreeSingleIndexDynamicAdaptor_ + index_container_t; + std::vector index; + +public: + /** Get a const ref to the internal list of indices; the number of indices is + * adapted dynamically as the dataset grows in size. */ + const std::vector &getAllIndices() const { return index; } + +private: + /** finds position of least significant unset bit */ + int First0Bit(IndexType num) { + int pos = 0; + while (num & 1) { + num = num >> 1; + pos++; + } + return pos; + } + + /** Creates multiple empty trees to handle dynamic support */ + void init() { + typedef KDTreeSingleIndexDynamicAdaptor_ + my_kd_tree_t; + std::vector index_( + treeCount, my_kd_tree_t(dim /*dim*/, dataset, treeIndex, index_params)); + index = index_; + } + +public: + Distance distance; + + /** + * KDTree constructor + * + * Refer to docs in README.md or online in + * https://github.com/jlblancoc/nanoflann + * + * The KD-Tree point dimension (the length of each point in the datase, e.g. 3 + * for 3D points) is determined by means of: + * - The \a DIM template parameter if >0 (highest priority) + * - Otherwise, the \a dimensionality parameter of this constructor. + * + * @param inputData Dataset with the input features + * @param params Basically, the maximum leaf node size + */ + KDTreeSingleIndexDynamicAdaptor(const int dimensionality, + const DatasetAdaptor &inputData, + const KDTreeSingleIndexAdaptorParams ¶ms = + KDTreeSingleIndexAdaptorParams(), + const size_t maximumPointCount = 1000000000U) + : dataset(inputData), index_params(params), distance(inputData) { + treeCount = static_cast(std::log2(maximumPointCount)); + pointCount = 0U; + dim = dimensionality; + treeIndex.clear(); + if (DIM > 0) + dim = DIM; + m_leaf_max_size = params.leaf_max_size; + init(); + const size_t num_initial_points = dataset.kdtree_get_point_count(); + if (num_initial_points > 0) { + addPoints(0, num_initial_points - 1); + } + } + + /** Deleted copy constructor*/ + KDTreeSingleIndexDynamicAdaptor( + const KDTreeSingleIndexDynamicAdaptor &) = delete; + + /** Add points to the set, Inserts all points from [start, end] */ + void addPoints(IndexType start, IndexType end) { + size_t count = end - start + 1; + treeIndex.resize(treeIndex.size() + count); + for (IndexType idx = start; idx <= end; idx++) { + int pos = First0Bit(pointCount); + index[pos].vind.clear(); + treeIndex[pointCount] = pos; + for (int i = 0; i < pos; i++) { + for (int j = 0; j < static_cast(index[i].vind.size()); j++) { + index[pos].vind.push_back(index[i].vind[j]); + if (treeIndex[index[i].vind[j]] != -1) + treeIndex[index[i].vind[j]] = pos; + } + index[i].vind.clear(); + index[i].freeIndex(index[i]); + } + index[pos].vind.push_back(idx); + index[pos].buildIndex(); + pointCount++; + } + } + + /** Remove a point from the set (Lazy Deletion) */ + void removePoint(size_t idx) { + if (idx >= pointCount) + return; + treeIndex[idx] = -1; + } + + /** + * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored + * inside the result object. + * + * Params: + * result = the result object in which the indices of the + * nearest-neighbors are stored vec = the vector for which to search the + * nearest neighbors + * + * \tparam RESULTSET Should be any ResultSet + * \return True if the requested neighbors could be found. + * \sa knnSearch, radiusSearch + */ + template + bool findNeighbors(RESULTSET &result, const ElementType *vec, + const SearchParams &searchParams) const { + for (size_t i = 0; i < treeCount; i++) { + index[i].findNeighbors(result, &vec[0], searchParams); + } + return result.full(); + } +}; + +/** An L2-metric KD-tree adaptor for working with data directly stored in an + * Eigen Matrix, without duplicating the data storage. You can select whether a + * row or column in the matrix represents a point in the state space. + * + * Example of usage: + * \code + * Eigen::Matrix mat; + * // Fill out "mat"... + * + * typedef KDTreeEigenMatrixAdaptor< Eigen::Matrix > + * my_kd_tree_t; const int max_leaf = 10; my_kd_tree_t mat_index(mat, max_leaf + * ); mat_index.index->buildIndex(); mat_index.index->... \endcode + * + * \tparam DIM If set to >0, it specifies a compile-time fixed dimensionality + * for the points in the data set, allowing more compiler optimizations. \tparam + * Distance The distance metric to use: nanoflann::metric_L1, + * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam row_major + * If set to true the rows of the matrix are used as the points, if set to false + * the columns of the matrix are used as the points. + */ +template +struct KDTreeEigenMatrixAdaptor { + typedef KDTreeEigenMatrixAdaptor self_t; + typedef typename MatrixType::Scalar num_t; + typedef typename MatrixType::Index IndexType; + typedef + typename Distance::template traits::distance_t metric_t; + typedef KDTreeSingleIndexAdaptor + index_t; + + index_t *index; //! The kd-tree index for the user to call its methods as + //! usual with any other FLANN index. + + /// Constructor: takes a const ref to the matrix object with the data points + KDTreeEigenMatrixAdaptor(const size_t dimensionality, + const std::reference_wrapper &mat, + const int leaf_max_size = 10) + : m_data_matrix(mat) { + const auto dims = row_major ? mat.get().cols() : mat.get().rows(); + if (size_t(dims) != dimensionality) + throw std::runtime_error( + "Error: 'dimensionality' must match column count in data matrix"); + if (DIM > 0 && int(dims) != DIM) + throw std::runtime_error( + "Data set dimensionality does not match the 'DIM' template argument"); + index = + new index_t(static_cast(dims), *this /* adaptor */, + nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size)); + index->buildIndex(); + } + +public: + /** Deleted copy constructor */ + KDTreeEigenMatrixAdaptor(const self_t &) = delete; + + ~KDTreeEigenMatrixAdaptor() { delete index; } + + const std::reference_wrapper m_data_matrix; + + /** Query for the \a num_closest closest points to a given point (entered as + * query_point[0:dim-1]). Note that this is a short-cut method for + * index->findNeighbors(). The user can also call index->... methods as + * desired. \note nChecks_IGNORED is ignored but kept for compatibility with + * the original FLANN interface. + */ + inline void query(const num_t *query_point, const size_t num_closest, + IndexType *out_indices, num_t *out_distances_sq, + const int /* nChecks_IGNORED */ = 10) const { + nanoflann::KNNResultSet resultSet(num_closest); + resultSet.init(out_indices, out_distances_sq); + index->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); + } + + /** @name Interface expected by KDTreeSingleIndexAdaptor + * @{ */ + + const self_t &derived() const { return *this; } + self_t &derived() { return *this; } + + // Must return the number of data points + inline size_t kdtree_get_point_count() const { + if(row_major) + return m_data_matrix.get().rows(); + else + return m_data_matrix.get().cols(); + } + + // Returns the dim'th component of the idx'th point in the class: + inline num_t kdtree_get_pt(const IndexType idx, size_t dim) const { + if(row_major) + return m_data_matrix.get().coeff(idx, IndexType(dim)); + else + return m_data_matrix.get().coeff(IndexType(dim), idx); + } + + // Optional bounding-box computation: return false to default to a standard + // bbox computation loop. + // Return true if the BBOX was already computed by the class and returned in + // "bb" so it can be avoided to redo it again. Look at bb.size() to find out + // the expected dimensionality (e.g. 2 or 3 for point clouds) + template bool kdtree_get_bbox(BBOX & /*bb*/) const { + return false; + } + + /** @} */ + +}; // end of KDTreeEigenMatrixAdaptor + /** @} */ + +/** @} */ // end of grouping +} // namespace nanoflann + +#endif /* NANOFLANN_HPP_ */ diff --git a/include/tag16h5.h b/include/tag16h5.h index e4302a8..60804c4 100644 --- a/include/tag16h5.h +++ b/include/tag16h5.h @@ -32,7 +32,7 @@ #ifndef _TAG16H5 #define _TAG16H5 -#include "lidar_tag.h" +#include "lidartag.h" BipedLab::GrizTagFamily_t *tag16h5_create(); void tag16h5_destroy(BipedLab::GrizTagFamily_t *tf); diff --git a/include/tag49h14.h b/include/tag49h14.h index 6c1fa29..6801e3b 100644 --- a/include/tag49h14.h +++ b/include/tag49h14.h @@ -31,7 +31,7 @@ #ifndef _TAG49H14 #define _TAG49H14 -#include "lidar_tag.h" +#include "lidartag.h" BipedLab::GrizTagFamily_t *tag49h14_create(); void tag49h14_destroy(BipedLab::GrizTagFamily_t *tf); diff --git a/include/thread_pool.h b/include/thread_pool.h new file mode 100644 index 0000000..d6feaf1 --- /dev/null +++ b/include/thread_pool.h @@ -0,0 +1,98 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace BipedLab { +class ThreadPool { +public: +ThreadPool (int threads) : + shutdown_ (false), + job_counter_(0) { + // Create the specified number of threads + threads_.reserve (threads); + for (int i = 0; i < threads; ++i) + threads_.emplace_back (std::bind (&ThreadPool::threadEntry, this, i)); +} + +~ThreadPool () { + { + // Unblock any threads and tell them to stop + std::unique_lock l (lock_); + + shutdown_ = true; + condVar_.notify_all(); + } + + // Wait for all threads to stop + std::cerr << "Joining threads" << std::endl; + for (auto& thread : threads_) + thread.join(); +} + +void enqueueTask(std::function func) { + // Place a job on the queu and unblock a thread + std::unique_lock l (lock_); + + jobs_.emplace (std::move (func)); + condVar_.notify_one(); +} + +void reset_counter() { + job_counter_ = 0; +} + +void wait_until_finished(int job_number) { + while (1) { + if (job_number == job_counter_) { + break; + } + } +} + + +protected: +void threadEntry (int i) +{ + std::function job; + + while (1) + { + { + std::unique_lock l (lock_); + + while (! shutdown_ && jobs_.empty()) + condVar_.wait (l); + + if (jobs_.empty ()) + { + // No jobs to do and we are shutting down + std::cerr << "Thread " << i << " terminates" << std::endl; + return; + } + + // std::cerr << "Thread " << i << " does a job" << std::endl; + job = std::move (jobs_.front ()); + jobs_.pop(); + job_counter_ ++; + } + + // Do the job without holding any locks + job (); + } +} + +std::atomic job_counter_; +std::mutex lock_; +std::condition_variable condVar_; +bool shutdown_; +std::queue > jobs_; +std::vector threads_; +}; +} // BipedLab namespace diff --git a/include/types.h b/include/types.h index 64d1a53..6f074c3 100644 --- a/include/types.h +++ b/include/types.h @@ -27,6 +27,11 @@ * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) * WEBSITE: https://www.brucerobot.com/ */ +#include +#include +#include // high_resolution_clock +#include "nanoflann.hpp" + namespace BipedLab { typedef velodyne_pointcloud::PointXYZIR PointXYZRI; @@ -64,11 +69,40 @@ namespace BipedLab { int max; } MaxMin_t; + struct angleComparision { + bool operator() (const float &i, const float &j) const { + // if (std::abs(i - j) > 0.0017) + // return true; + // else + // return false; + // return (std::abs(i - j) > 0.004); + //return (std::abs(i - j) > 0.005); + // const int i_int = static_cast(i * 1000); + // const int j_int = static_cast(j * 1000); + // return i_int < j_int; + + float threshold = 0.3; + if (std::abs(i - j) < threshold) { + return false; + } else { + return i < j; + } + } + // bool operator() (const pair &lhs, const pair &rhs) const{ + // return (lhs.second - lhs.first > rhs.second - rhs.first); + // } + }; + + // Structure for LiDAR system typedef struct LiDARSystem { std::vector> point_count_table; // point per ring PointCountTable[Scan][ring] std::vector max_min_table; // max min points in a scan std::vector ring_average_table; // max, min, average points in a ring, examed through out a few seconds + // std::vector angle_list; // store the angle of each point + std::set angle_list; + + double points_per_square_meter_at_one_meter; // TODO: only assume place the tag at dense-point area double beam_per_vertical_radian; double point_per_horizontal_radian; @@ -78,8 +112,9 @@ namespace BipedLab { typedef struct LiDARPoints { PointXYZRI point; int index; - double depth_gradient; // only take abs value due to uncertain direction - double intensity_gradient; // Also account for direction by knowing tag is white to black + int valid; + double tag_size; // only take abs value due to uncertain direction + double box_width; // Also account for direction by knowing tag is white to black double threshold_intensity; } LiDARPoints_t; @@ -122,10 +157,29 @@ namespace BipedLab { float cy; } Grid_t; + typedef struct RKHSDecoding{ + Eigen::MatrixXf initial_template_points; + Eigen::MatrixXf template_points; + Eigen::MatrixXf template_points_xyz; + Eigen::VectorXf template_points_feat; + Eigen::MatrixXf template_points_3d; + Eigen::MatrixXf *associated_pattern_3d; + std::vector score; + int num_points; + int size_num; + int rotation_angle; + double ell; + double ave_intensity; + int id; + float id_score; + }RKHSDecoding_t; + typedef struct ClusterFamily { // EIGEN_MAKE_ALIGNED_OPERATOR_NEW int cluster_id; int valid; + int top_ring; + int bottom_ring; PointXYZRI top_most_point; PointXYZRI bottom_most_point; @@ -138,7 +192,15 @@ namespace BipedLab { PointXYZRI average; // Average point PointXYZRI max_intensity; // Maximux intensity point PointXYZRI min_intensity; // Minimum intensity point - pcl::PointCloud data; + pcl::PointCloud data; //data doesn't have edge points + pcl::PointCloud edge_points; + pcl::PointCloud transformed_edge_points; + + // If the first point of the ring is the cluster. + // If so, the the indices fo the two sides will be far away + int special_case; + Eigen::MatrixXf merged_data; // this includes edge and filled-in points + Eigen::MatrixXf merged_data_h; // this includes edge and filled-in points std::vector max_min_index_of_each_ring; // to fill in points between end points in this cluster std::vector> ordered_points_ptr; // of the cluster (to find black margin of the tag) @@ -149,15 +211,34 @@ namespace BipedLab { std::vector payload_right_boundary_ptr; // of the cluster (to find black margin of the tag) std::vector payload_left_boundary_ptr; // of the cluster (to find black margin of the tag) std::vector payload_boundary_ptr; // of the cluster (to find black margin of the tag) - + int data_inliers; + int edge_inliers; + int inliers; + double percentages_inliers; + int boundary_pts; + int boundary_rings; pcl::PointCloud payload; // payload points with boundary + pcl::PointCloud RLHS_decoding; // payload points transformed int payload_without_boundary; // size of payload points without boundary + double tag_size; + double box_width; + + pcl::PointCloud edge_group1; + pcl::PointCloud edge_group2; + pcl::PointCloud edge_group3; + pcl::PointCloud edge_group4; + // Eigen::Vector3f NormalVector; // Normal vectors of the payload Eigen::Matrix normal_vector; + Eigen::Matrix principal_axes; QuickDecodeEntry_t entry; + Homogeneous_t pose_tag_to_lidar; Homogeneous_t pose; + Homogeneous_t initial_pose; tf::Transform transform; + RKHSDecoding_t rkhs_decoding; // + /* VectorXf: @@ -197,13 +278,20 @@ namespace BipedLab { }GrizTagFamily_t; typedef struct ClusterRemoval { - int removed_by_point_check; - int boundary_point_check; - int no_edge_check; int minimum_return; - int decode_fail; - int decoder_not_return; - int decoder_fail_corner; + int maximum_return; + int plane_fitting; // v + int plane_outliers; // v + int boundary_point_check; // v + int minimum_ring_points; + int no_edge_check; // v + int line_fitting; + int pose_optimization; + int decoding_failure; + + // for weighted gaussian + int decoder_not_return; + int decoder_fail_corner; }ClusterRemoval_t; typedef struct Statistics { @@ -215,23 +303,47 @@ namespace BipedLab { }Statistics_t; typedef struct Timing{ - // in us - clock_t start_total_time; - clock_t start_computation_time; - clock_t timing; + // in ms + std::chrono::steady_clock::time_point start_total_time; + std::chrono::steady_clock::time_point start_computation_time; + std::chrono::steady_clock::time_point timing; + double duration; double total_time; - double computation_time; - double edgingand_clustering_time; + double total_duration; + double edging_and_clustering_time; double to_pcl_vector_time; + double fill_in_time; double point_check_time; + double plane_fitting_removal_time; double line_fitting_time; - double payload_extraction_time; - double normal_vector_time; + double organize_points_time; + double pca_time; + double split_edge_time; + double pose_optimization_time; + double store_template_time; double payload_decoding_time; + + + + double normal_vector_time; double tag_to_robot_time; }Timing_t; + typedef struct TimeDecoding{ + // in ms + std::chrono::steady_clock::time_point timing; + + double original; + double matrix; + double vectorization; + double tbb_original; + double tbb_vectorization; + double manual_scheduling_tbb_vectorization; + double tbb_scheduling_tbb_vectorization; + double tbb_kd_tree; + }TimeDecoding_t; + typedef struct TestCluster { int flag; ClusterFamily_t new_cluster; @@ -243,4 +355,22 @@ namespace BipedLab { std::vector no_edge; std::vector extract_payload; }Debug_t; + + + typedef struct PathLeafString{ + std::string operator()(const boost::filesystem::directory_entry& entry) const { + return entry.path().leaf().string(); + } + }PathLeafString_t; + + typedef nanoflann::KDTreeEigenMatrixAdaptor< + Eigen::Matrix, -1, + nanoflann::metric_L2, + false> kd_tree_t; + + typedef Eigen::Triplet Trip_t; + + + + } // namespace diff --git a/include/ultra_puck.h b/include/ultra_puck.h new file mode 100644 index 0000000..83b7b3a --- /dev/null +++ b/include/ultra_puck.h @@ -0,0 +1,102 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + +#ifndef ULTRA_PUCK_H +#define ULTRA_PuCK_H + +namespace BipedLab +{ +namespace UltraPuckV2 +{ +// Number of beams in Velodyne Ultra Puck 2.0 +constexpr int beams = 32; + +/* el holds the elevation angle information for each ring in the UltraPuckV2. + * The number to the right of the elevation angle is the hardware laser id + * which can be found in the VLP-32C manual. + */ +constexpr float el[] = { + -25.0, // 0 + -15.639, // 3 + -11.310, // 4 + -8.843, // 7 + -7.254, // 8 + -6.148, // 11 + -5.333, // 12 + -4.667, // 16 + -4.0, // 15 + -3.667, // 19 + -3.333, // 20 + -3.0, // 24 + -2.667, // 23 + -2.333, // 27 + -2.0, // 28 + -1.667, // 2 + -1.333, // 31 + -1.0, // 1 + -0.667, // 6 + -0.333, // 10 + 0.0, // 5 + 0.333, // 9 + 0.667, // 14 + 1.0, // 18 + 1.333, // 13 + 1.667, // 17 + 2.333, // 22 + 3.333, // 21 + 4.667, // 26 + 7.0, // 25 + 10.333, // 30 + 15.0 // 29 +}; + +constexpr float AZ_RESOLUTION_300RPM = 0.1; +constexpr float AZ_RESOLUTION_600RPM = 0.2; +constexpr float AZ_RESOLUTION_900RPM = 0.3; +constexpr float AZ_RESOLUTION_1200RPM = 0.4; + +struct EL_TABLE +{ + constexpr EL_TABLE() : values() + { + for (auto i = 0; i < 32; ++i) { + values[i] = tan(el[i]*M_PI/180); + } + } + + int values[32]; +}; + +constexpr EL_TABLE EL_TAN = EL_TABLE(); + +} // namespace UltraPuckV2 +} // namespace BipedLab + +#endif diff --git a/include/utils.h b/include/utils.h index 389b217..f4b347e 100644 --- a/include/utils.h +++ b/include/utils.h @@ -33,139 +33,428 @@ #define UTILS_H #include +#include #include // to use to_lower function #include // for variadic functions #include +// #include +//#include +#include + #include #include -#include "lidar_tag.h" +#include "lidartag.h" namespace BipedLab { - //typedef velodyne_pointcloud::PointXYZIR PointXYZRI; - namespace utils { - double spendTime(const std::clock_t &t_end, const std::clock_t &t_start); - std::string tranferToLowercase(std::string &t_data); - void pressEnterToContinue(); - double deg2Rad(double t_degree); - double rad2Deg(double t_radian); - bool isRotationMatrix(Eigen::Matrix3f &t_R); - Eigen::Vector3f rotationMatrixToEulerAngles(Eigen::Matrix3f &t_R); +//typedef velodyne_pointcloud::PointXYZIR PointXYZRI; +namespace utils { +double spendCPUTime(const std::clock_t &t_end, const std::clock_t &t_start); +double spendCPUHz(const std::clock_t &t_end, const std::clock_t &t_start); +double printSpendCPUHz( + const std::clock_t &t_end, const std::clock_t &t_start); +double printSpendCPUHz( + const std::clock_t &t_end, const std::clock_t &t_start, std::string txt); + +double spendElapsedTimeMilli( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start); + +double spendElapsedTime( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start); + +double spendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start); + +double printSpendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start, + std::string txt); + +double printSpendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start); + + + +// bool angleComparision (float i, float j); + + + + + +/* + * Generic function to find an element in vector and also its position. + * It returns a pair of bool & int i.e. + * bool : Represents if element is present in vector or not. + * int : Represents the index of element in vector if its found else -1 +*/ +template < typename T> +std::pair findInVector(const std::vector &vecOfElements, const T &element) { + std::pair result; + // Find given element in vector + auto it = std::find(vecOfElements.begin(), vecOfElements.end(), element); + if (it != vecOfElements.end()) + { + result.second = distance(vecOfElements.begin(), it); + result.first = true; + } + else + { + result.first = false; + result.second = -1; + } + return result; +} + + + + +std::string tranferToLowercase(std::string &t_data); + +void pressEnterToContinue(); - bool checkParameters(int t_n, ...); - void COUT(const velodyne_pointcloud::PointXYZIR& t_p); - bool compareIndex(LiDARPoints_t *A, LiDARPoints_t *B); - uint64_t bitShift(std::string const& t_value); +template +T deg2Rad(T t_degree){ + return t_degree*M_PI/180; +} +template +T rad2Deg(T t_radian){ + return t_radian*180/M_PI; +} +bool isRotationMatrix(Eigen::Matrix3f &t_R); +Eigen::Vector3f rotationMatrixToEulerAngles(Eigen::Matrix3f &t_R); - void normalizeByAve(std::vector &t_x, std::vector &t_y, - std::vector &t_z, std::vector &t_I, - const pcl::PointCloud payload); - void normalize(std::vector &t_x, std::vector &t_y, - std::vector &t_z, std::vector &t_I, - const pcl::PointCloud t_payload); - velodyne_pointcloud::PointXYZIR pointsAddDivide ( - const velodyne_pointcloud::PointXYZIR& t_p1, - const velodyne_pointcloud::PointXYZIR& t_p2, float t_d=1); +bool checkParameters(int t_n, ...); +void COUT(const velodyne_pointcloud::PointXYZIR& t_p); +bool compareIndex(LiDARPoints_t *A, LiDARPoints_t *B); +uint64_t bitShift(std::string const& t_value); - velodyne_pointcloud::PointXYZIR vectorize ( - const velodyne_pointcloud::PointXYZIR& t_p1, - const velodyne_pointcloud::PointXYZIR& t_p2); - float dot (const velodyne_pointcloud::PointXYZIR& t_p1, - const velodyne_pointcloud::PointXYZIR& t_p2); - float Norm (const velodyne_pointcloud::PointXYZIR& t_p); +void normalizeByAve(std::vector &t_x, std::vector &t_y, + std::vector &t_z, std::vector &t_I, + const pcl::PointCloud payload); +void normalize(std::vector &t_x, std::vector &t_y, + std::vector &t_z, std::vector &t_I, + const pcl::PointCloud t_payload); - // a function to determine the step of given two points - float getStep(const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, const int t_d); +velodyne_pointcloud::PointXYZIR pointsAddDivide ( + const velodyne_pointcloud::PointXYZIR& t_p1, + const velodyne_pointcloud::PointXYZIR& t_p2, float t_d=1); - void getProjection(const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, - const velodyne_pointcloud::PointXYZIR &t_p, - float &t_k, Eigen::Vector2f &t_v); +velodyne_pointcloud::PointXYZIR vectorize ( + const velodyne_pointcloud::PointXYZIR& t_p1, + const velodyne_pointcloud::PointXYZIR& t_p2); - double MVN(const float &t_tag_size, const int &t_d, - const Eigen::Vector2f &t_X, const Eigen::Vector2f t_mean); +float dot (const velodyne_pointcloud::PointXYZIR& t_p1, + const velodyne_pointcloud::PointXYZIR& t_p2); - void assignCellIndex(const float &t_tag_size, - const Eigen::Matrix3f &t_R, - velodyne_pointcloud::PointXYZIR &t_p_reference, - const velodyne_pointcloud::PointXYZIR &t_average, - const int t_d, PayloadVoting_t &t_vote); +float Norm (const velodyne_pointcloud::PointXYZIR& t_p); - void sortPointsToGrid(std::vector> &t_grid, - std::vector &t_votes); +// a function to determine the step of given two points +float getStep(const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, const int t_d); - Eigen::Vector2f pointToLine(const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, - const velodyne_pointcloud::PointXYZIR &t_p); +void getProjection(const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, + const velodyne_pointcloud::PointXYZIR &t_p, + float &t_k, Eigen::Vector2f &t_v); - void formGrid(Eigen::MatrixXf &t_vertices, - float t_x, float t_y, float t_z, float t_tag_size); +double MVN(const float &t_tag_size, const int &t_d, + const Eigen::Vector2f &t_X, const Eigen::Vector2f t_mean); - void fitGrid(Eigen::MatrixXf &t_vertices, - Eigen::Matrix3f &t_R, - const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, - const velodyne_pointcloud::PointXYZIR &t_p3, - const velodyne_pointcloud::PointXYZIR &t_p4); +void assignCellIndex(const float &t_tag_size, + const Eigen::Matrix3f &t_R, + velodyne_pointcloud::PointXYZIR &t_p_reference, + const velodyne_pointcloud::PointXYZIR &t_average, + const int t_d, PayloadVoting_t &t_vote); - float distance( - const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2); - template - float getAngle (T a, U b); +void sortPointsToGrid(std::vector> &t_grid, + std::vector &t_votes); +Eigen::Vector2f pointToLine(const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, + const velodyne_pointcloud::PointXYZIR &t_p); - int checkCorners( - const float t_tag_size, - const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, - const velodyne_pointcloud::PointXYZIR &t_p3, - const velodyne_pointcloud::PointXYZIR &t_p4); +void formGrid(Eigen::MatrixXf &t_vertices, + float t_x, float t_y, float t_z, float t_tag_size); - velodyne_pointcloud::PointXYZIR toVelodyne(const Eigen::Vector3f &t_p); - Eigen::Vector3f toEigen(const velodyne_pointcloud::PointXYZIR &t_point); - void minus(velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2); +void fitGrid(Eigen::MatrixXf &t_vertices, + Eigen::Matrix3f &t_R, + const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, + const velodyne_pointcloud::PointXYZIR &t_p3, + const velodyne_pointcloud::PointXYZIR &t_p4); - template - T blockMatrix(int t_n, ...); +void fitGrid_new(Eigen::MatrixXf &t_vertices, Eigen::Matrix3f &H, + Eigen::MatrixXf &t_payload_vertices); +float distance( + const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2); +template +float getAngle (T a, U b); +double get_sign(double x); +Eigen::Matrix3f +skew(const Eigen::Vector3d t_v); - // template - Eigen::Matrix4d poseToEigenMatrix(const geometry_msgs::Pose &t_pose); - // Eigen::Matrix4d poseToEigenMatrix(const T &pose); +Eigen::Matrix3f +Exp_SO3(const Eigen::Vector3d t_w); - template - Eigen::Matrix3d qToR(const T &t_pose); +Eigen::Vector3d +unskew(const Eigen::Matrix3f t_Ax); - Eigen::Matrix3d qToR(const Eigen::Vector3f &t_pose); +Eigen::Vector3d +Log_SO3(const Eigen::Matrix3f t_A); - // q1q2 = q2q1q2^-1 - Eigen::Matrix3d qMultiplication(const double &t_q1_w, const Eigen::Vector3f &t_q1, - const double &t_q2_w, const Eigen::Vector3f &t_q2); +int checkCorners( + const float t_tag_size, + const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, + const velodyne_pointcloud::PointXYZIR &t_p3, + const velodyne_pointcloud::PointXYZIR &t_p4); +velodyne_pointcloud::PointXYZIR toVelodyne(const Eigen::Vector3f &t_p); +Eigen::Vector3f toEigen(const velodyne_pointcloud::PointXYZIR &t_point); +void minus(velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2); - template - bool goodNumber(T t_number){ - if (std::isinf(t_number) || std::isnan(t_number)) - return false; - else return true; +template +T blockMatrix(int t_n, ...); + + +// template +Eigen::Matrix4d poseToEigenMatrix(const geometry_msgs::Pose &t_pose); +// Eigen::Matrix4d poseToEigenMatrix(const T &pose); + +template +Eigen::Matrix3d qToR(const T &t_pose); + +Eigen::Matrix3d qToR(const Eigen::Vector3f &t_pose); + +// q1q2 = q2q1q2^-1 +Eigen::Matrix3d qMultiplication(const double &t_q1_w, const Eigen::Vector3f &t_q1, + const double &t_q2_w, const Eigen::Vector3f &t_q2); + + +template +bool goodNumber(T t_number){ + if (std::isinf(t_number) || std::isnan(t_number)) + return false; + else return true; +} + +/* + * Removes all undesired elements in vec listed by index in rm + */ +template < typename T, template class C> +void removeIndicesFromVector(C& c, std::vector& rm) { + + using std::begin; + using std::end; + + // If indices in rm are not sorted, sort + if (!std::is_sorted(rm.begin(), rm.end())) { + std::sort(rm.begin(), rm.end()); + } + + auto rm_iter = rm.begin(); + std::size_t curr_idx = 0; + + const auto pred = [&](const T& /*val*/) { + // Any more to remove? + if (rm_iter == rm.end()) { + return false; + } + + // Does current index match remove index + if (*rm_iter == curr_idx++) { + ++rm_iter; + return true; } + return false; + }; + + c.erase(std::remove_if(begin(c), end(c), pred), end(c)); +} +std::vector complementOfSet(const std::vector& set, std::size_t n); +// std::ostream& operator<<(std::ostream& os, const velodyne_pointcloud::PointXYZIR& p); +float dot_product(Eigen::Vector3f v1, Eigen::Vector3f v2); +Eigen::Vector3f cross_product(Eigen::Vector3f v1, Eigen::Vector3f v2); - // std::ostream& operator<<(std::ostream& os, const velodyne_pointcloud::PointXYZIR& p); +/* A function to read data in a csv file + * and load the data to an eigen matrix + */ +template +M loadCSV (const std::string &path){ + std::ifstream indata; + indata.open(path); + std::string line; + std::vector values; + uint rows = 0; + while (std::getline(indata, line)) { + std::stringstream lineStream(line); + std::string cell; + while (std::getline(lineStream, cell, ',')) { + values.push_back(std::stod(cell)); + } + ++rows; } + + return Eigen::Map>(values.data(), + rows, values.size()/rows); +} + + +/* A function to read files from a folder + * + */ +void readDirectory(const std::string& name, std::vector &v); + + +/* A function to compute the median of a eigen vector + */ +float computeMedian(const Eigen::VectorXf &eigen_vec); + + +template +void printVector(const std::vector &vec){ + std::copy(vec.begin(), vec.end(), + std::ostream_iterator(std::cout, "\n")); +} + +template +std::vector +convertEigenToSTDVector(const T &mat) { + std::vector vec(mat.data(), mat.data() + mat.rows() * mat.cols()); + + return vec; +} + +Eigen::MatrixXf +convertXYZIToHomogeneous(const Eigen::MatrixXf &mat_xyzi); + + +template +Eigen::Matrix3f computeRotX(T deg){ + T rad = deg2Rad(deg); + Eigen::Matrix3f rotx; + rotx << 1, 0, 0, + 0, std::cos(rad), -std::sin(rad), + 0, std::sin(rad), std::cos(rad); + + return rotx; +} + +template +Eigen::Matrix3f computeRotY(T deg){ + T rad = deg2Rad(deg); + Eigen::Matrix3f roty; + roty << std::cos(rad), 0, std::sin(rad), + 0, 1, 0, + -std::sin(rad), 0, std::cos(rad); + + return roty; +} + +template +Eigen::Matrix3f computeRotZ(T deg){ + T rad = deg2Rad(deg); + Eigen::Matrix3f rotz; + rotz << std::cos(rad), -std::sin(rad), 0, + std::sin(rad), std::cos(rad), 0, + 0, 0, 1; + + return rotz; +} + + +double cross( +const Eigen::Vector4f &O, const Eigen::Vector4f &A, const Eigen::Vector4f &B); + +Eigen::Matrix4f +computeTransformation (Eigen::Vector3f rot_v, Eigen::Vector3f trans_v); + +void sortEigenVectorIndices(const Eigen::VectorXf &v, Eigen::VectorXi &indices); +void constructConvexHull(const Eigen::MatrixXf &P, Eigen::MatrixXf &convex_hull); + +float computePolygonArea(const Eigen::MatrixXf &vertices); + + + + //float computeMedian(std::vector vec); + // template + // T computeMedian(std::vector &vec); + // template + // T computeMedian(std::vector &vec){ + // assert(vec.size()!=0); + // if (vec.size() % 2 == 0) { + // const auto median_it1 = vec.begin() + vec.size() / 2 - 1; + // const auto median_it2 = vec.begin() + vec.size() / 2; + + // std::nth_element(vec.begin(), median_it1 , vec.end()); + // const T e1 = *median_it1; + + // std::nth_element(vec.begin(), median_it2 , vec.end()); + // const T e2 = *median_it2; + + // return (e1 + e2) / 2; + + // } else { + // const auto median_it = vec.begin() + vec.size() / 2; + // std::nth_element(vec.begin(), median_it , vec.end()); + + // return *median_it; + // } + // } + + + + + + // auto computeMedian(const std::vector &vec); + // template + // T computeMedian(const std::vector &eigen_vec); + // template + // T computeMedian(const std::vector &vec){ + // //assert(eigen_vec.size()!=0); + // //std::vector vec(eigen_vec.data(), eigen_vec.data() + eigen_vec.size()); + // assert(vec.size()!=0); + // if (vec.size() % 2 == 0) { + // const T median_it1 = vec.begin() + vec.size() / 2 - 1; + // const T median_it2 = vec.begin() + vec.size() / 2; + + // std::nth_element(vec.begin(), median_it1 , vec.end()); + // const T e1 = *median_it1; + + // std::nth_element(vec.begin(), median_it2 , vec.end()); + // const T e2 = *median_it2; + + // return (e1 + e2) / 2; + + // } else { + // const T median_it = vec.begin() + vec.size() / 2; + // std::nth_element(vec.begin(), median_it , vec.end()); + + // return *median_it; + // } + // } + + +} // utils } // Bipedlab #endif diff --git a/launch/H3D.launch b/launch/H3D.launch new file mode 100644 index 0000000..86cffd2 --- /dev/null +++ b/launch/H3D.launch @@ -0,0 +1,178 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/LiDARTag.launch b/launch/LiDARTag.launch index c2d58b5..0593834 100644 --- a/launch/LiDARTag.launch +++ b/launch/LiDARTag.launch @@ -1,76 +1,161 @@ - + - - + + + - - - - - + + + + - + + + + - + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] - - - + + + + + - - - + + + + - - - - - + + + + - - - - - + + + - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - + + + + - - - - + + - - + + + + + + \ No newline at end of file diff --git a/launch/LiDARTag_backup.launch b/launch/LiDARTag_backup.launch new file mode 100644 index 0000000..e79f931 --- /dev/null +++ b/launch/LiDARTag_backup.launch @@ -0,0 +1,143 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/LiDARTag_indoor.launch b/launch/LiDARTag_indoor.launch new file mode 100644 index 0000000..0e2570c --- /dev/null +++ b/launch/LiDARTag_indoor.launch @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + [0.8051, 0.61] + + + diff --git a/launch/LiDARTag_main.launch b/launch/LiDARTag_main.launch new file mode 100644 index 0000000..53ed8eb --- /dev/null +++ b/launch/LiDARTag_main.launch @@ -0,0 +1,194 @@ + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.61] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/LiDARTag_master.launch b/launch/LiDARTag_master.launch new file mode 100644 index 0000000..7d60f1a --- /dev/null +++ b/launch/LiDARTag_master.launch @@ -0,0 +1,184 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/LiDARTag_outdoor.launch b/launch/LiDARTag_outdoor.launch new file mode 100644 index 0000000..f10da16 --- /dev/null +++ b/launch/LiDARTag_outdoor.launch @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + diff --git a/launch/LiDARTag_smallest.launch b/launch/LiDARTag_smallest.launch new file mode 100644 index 0000000..bff8d08 --- /dev/null +++ b/launch/LiDARTag_smallest.launch @@ -0,0 +1,49 @@ + + + + + + + + + [0.61] + + + + + + + + + + + diff --git a/launch/LiDARTag_threetags.launch b/launch/LiDARTag_threetags.launch new file mode 100644 index 0000000..80a1451 --- /dev/null +++ b/launch/LiDARTag_threetags.launch @@ -0,0 +1,49 @@ + + + + + + + + + [0.8051, 0.61, 1.22] + + + + + + + + + + + diff --git a/launch/LiDARTag_twotags.launch b/launch/LiDARTag_twotags.launch new file mode 100644 index 0000000..830faaf --- /dev/null +++ b/launch/LiDARTag_twotags.launch @@ -0,0 +1,49 @@ + + + + + + + + + [0.61, 0.8051] + + + + + + + + + + + diff --git a/launch/cartographer.launch b/launch/cartographer.launch new file mode 100644 index 0000000..6037285 --- /dev/null +++ b/launch/cartographer.launch @@ -0,0 +1,187 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/kitti.launch b/launch/kitti.launch new file mode 100644 index 0000000..34f6dd1 --- /dev/null +++ b/launch/kitti.launch @@ -0,0 +1,180 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/lidar_bh.launch b/launch/lidar_bh.launch new file mode 100644 index 0000000..0e2e1c5 --- /dev/null +++ b/launch/lidar_bh.launch @@ -0,0 +1,142 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/standlone_indoor_bh.launch b/launch/standlone_indoor_bh.launch new file mode 100644 index 0000000..15584fb --- /dev/null +++ b/launch/standlone_indoor_bh.launch @@ -0,0 +1,160 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/standlone_outdoor_bh.launch b/launch/standlone_outdoor_bh.launch new file mode 100644 index 0000000..dcdfe8d --- /dev/null +++ b/launch/standlone_outdoor_bh.launch @@ -0,0 +1,159 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [0.8051, 0.158, 1.22] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lib/0/tag16_06_00000_geometry.csv b/lib/0/tag16_06_00000_geometry.csv new file mode 100644 index 0000000..1eb2461 --- /dev/null +++ b/lib/0/tag16_06_00000_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00001_geometry.csv b/lib/0/tag16_06_00001_geometry.csv new file mode 100644 index 0000000..5a97ab7 --- /dev/null +++ b/lib/0/tag16_06_00001_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00002_geometry.csv b/lib/0/tag16_06_00002_geometry.csv new file mode 100644 index 0000000..aa7b3f5 --- /dev/null +++ b/lib/0/tag16_06_00002_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00003_geometry.csv b/lib/0/tag16_06_00003_geometry.csv new file mode 100644 index 0000000..c671dab --- /dev/null +++ b/lib/0/tag16_06_00003_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00004_geometry.csv b/lib/0/tag16_06_00004_geometry.csv new file mode 100644 index 0000000..432a5d7 --- /dev/null +++ b/lib/0/tag16_06_00004_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00005_geometry.csv b/lib/0/tag16_06_00005_geometry.csv new file mode 100644 index 0000000..12e8eb1 --- /dev/null +++ b/lib/0/tag16_06_00005_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00006_geometry.csv b/lib/0/tag16_06_00006_geometry.csv new file mode 100644 index 0000000..722f4eb --- /dev/null +++ b/lib/0/tag16_06_00006_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00007_geometry.csv b/lib/0/tag16_06_00007_geometry.csv new file mode 100644 index 0000000..96a15d9 --- /dev/null +++ b/lib/0/tag16_06_00007_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/0/tag16_06_00008_geometry.csv b/lib/0/tag16_06_00008_geometry.csv new file mode 100644 index 0000000..d6e0207 --- /dev/null +++ b/lib/0/tag16_06_00008_geometry.csv @@ -0,0 +1,4 @@ +0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,-0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125,0.038125 +-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.292291666666668,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.266875000000001,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.241458333333335,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.216041666666668,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.190625000000001,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.165208333333335,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.139791666666668,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.114375000000001,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0889583333333346,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0635416666666679,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0381250000000012,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,-0.0127083333333346,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.012708333333332,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0381249999999987,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0635416666666654,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.0889583333333321,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.114374999999999,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.139791666666665,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.165208333333332,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.190624999999999,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.216041666666665,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.241458333333332,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.266874999999999,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665,0.292291666666665 +-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666,-0.292291666666667,-0.266875000000001,-0.241458333333334,-0.216041666666667,-0.190625000000001,-0.165208333333334,-0.139791666666667,-0.114375000000001,-0.0889583333333341,-0.0635416666666674,-0.0381250000000007,-0.0127083333333341,0.0127083333333325,0.0381249999999992,0.0635416666666659,0.0889583333333326,0.114374999999999,0.139791666666666,0.165208333333333,0.190624999999999,0.216041666666666,0.241458333333333,0.266874999999999,0.292291666666666 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00000_geometry.csv b/lib/1/tag16_06_00000_geometry.csv new file mode 100644 index 0000000..e11574d --- /dev/null +++ b/lib/1/tag16_06_00000_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00001_geometry.csv b/lib/1/tag16_06_00001_geometry.csv new file mode 100644 index 0000000..6894b26 --- /dev/null +++ b/lib/1/tag16_06_00001_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00002_geometry.csv b/lib/1/tag16_06_00002_geometry.csv new file mode 100644 index 0000000..e433c30 --- /dev/null +++ b/lib/1/tag16_06_00002_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00003_geometry.csv b/lib/1/tag16_06_00003_geometry.csv new file mode 100644 index 0000000..157bea6 --- /dev/null +++ b/lib/1/tag16_06_00003_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00004_geometry.csv b/lib/1/tag16_06_00004_geometry.csv new file mode 100644 index 0000000..2e592b3 --- /dev/null +++ b/lib/1/tag16_06_00004_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00005_geometry.csv b/lib/1/tag16_06_00005_geometry.csv new file mode 100644 index 0000000..a2c8578 --- /dev/null +++ b/lib/1/tag16_06_00005_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00006_geometry.csv b/lib/1/tag16_06_00006_geometry.csv new file mode 100644 index 0000000..992c74a --- /dev/null +++ b/lib/1/tag16_06_00006_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00007_geometry.csv b/lib/1/tag16_06_00007_geometry.csv new file mode 100644 index 0000000..da2afdf --- /dev/null +++ b/lib/1/tag16_06_00007_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/1/tag16_06_00008_geometry.csv b/lib/1/tag16_06_00008_geometry.csv new file mode 100644 index 0000000..4e52876 --- /dev/null +++ b/lib/1/tag16_06_00008_geometry.csv @@ -0,0 +1,4 @@ +0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,-0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875,0.05031875 +-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.385777083333335,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.352231250000001,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.318685416666668,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.285139583333335,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.251593750000001,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.218047916666668,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.184502083333335,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.150956250000001,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.117410416666668,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0838645833333346,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.0503187500000013,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,-0.016772916666668,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0167729166666654,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.0503187499999987,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.083864583333332,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.117410416666665,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.150956249999999,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.184502083333332,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.218047916666665,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.251593749999999,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.285139583333332,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.318685416666665,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.352231249999999,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332,0.385777083333332 +-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333,-0.385777083333334,-0.352231250000001,-0.318685416666667,-0.285139583333334,-0.251593750000001,-0.218047916666667,-0.184502083333334,-0.150956250000001,-0.117410416666667,-0.0838645833333341,-0.0503187500000007,-0.0167729166666674,0.0167729166666659,0.0503187499999992,0.0838645833333326,0.117410416666666,0.150956249999999,0.184502083333333,0.218047916666666,0.251593749999999,0.285139583333333,0.318685416666666,0.352231249999999,0.385777083333333 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00000_geometry.csv b/lib/2/tag16_06_00000_geometry.csv new file mode 100644 index 0000000..e3240c0 --- /dev/null +++ b/lib/2/tag16_06_00000_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00001_geometry.csv b/lib/2/tag16_06_00001_geometry.csv new file mode 100644 index 0000000..83a196c --- /dev/null +++ b/lib/2/tag16_06_00001_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00002_geometry.csv b/lib/2/tag16_06_00002_geometry.csv new file mode 100644 index 0000000..90ec260 --- /dev/null +++ b/lib/2/tag16_06_00002_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00003_geometry.csv b/lib/2/tag16_06_00003_geometry.csv new file mode 100644 index 0000000..1afed96 --- /dev/null +++ b/lib/2/tag16_06_00003_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00004_geometry.csv b/lib/2/tag16_06_00004_geometry.csv new file mode 100644 index 0000000..b1f9929 --- /dev/null +++ b/lib/2/tag16_06_00004_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00005_geometry.csv b/lib/2/tag16_06_00005_geometry.csv new file mode 100644 index 0000000..d48cf53 --- /dev/null +++ b/lib/2/tag16_06_00005_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00006_geometry.csv b/lib/2/tag16_06_00006_geometry.csv new file mode 100644 index 0000000..2d16b9b --- /dev/null +++ b/lib/2/tag16_06_00006_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00007_geometry.csv b/lib/2/tag16_06_00007_geometry.csv new file mode 100644 index 0000000..b945c96 --- /dev/null +++ b/lib/2/tag16_06_00007_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/2/tag16_06_00008_geometry.csv b/lib/2/tag16_06_00008_geometry.csv new file mode 100644 index 0000000..713aa4b --- /dev/null +++ b/lib/2/tag16_06_00008_geometry.csv @@ -0,0 +1,4 @@ +0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,-0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625,0.07625 +-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.584583333333336,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.533750000000003,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.482916666666669,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.432083333333336,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.381250000000003,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.330416666666669,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.279583333333336,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.228750000000003,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.177916666666669,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.127083333333336,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0762500000000025,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,-0.0254166666666692,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0254166666666641,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.0762499999999975,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.127083333333331,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.177916666666664,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.228749999999997,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.279583333333331,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.330416666666664,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.381249999999997,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.432083333333331,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.482916666666664,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.533749999999998,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331,0.584583333333331 +-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332,-0.584583333333335,-0.533750000000002,-0.482916666666668,-0.432083333333335,-0.381250000000002,-0.330416666666668,-0.279583333333335,-0.228750000000002,-0.177916666666668,-0.127083333333335,-0.0762500000000015,-0.0254166666666682,0.0254166666666651,0.0762499999999985,0.127083333333332,0.177916666666665,0.228749999999998,0.279583333333332,0.330416666666665,0.381249999999998,0.432083333333332,0.482916666666665,0.533749999999999,0.584583333333332 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00000_geometry.csv b/lib/3/tag16_06_00000_geometry.csv new file mode 100644 index 0000000..29cf329 --- /dev/null +++ b/lib/3/tag16_06_00000_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00001_geometry.csv b/lib/3/tag16_06_00001_geometry.csv new file mode 100644 index 0000000..7808d41 --- /dev/null +++ b/lib/3/tag16_06_00001_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00002_geometry.csv b/lib/3/tag16_06_00002_geometry.csv new file mode 100644 index 0000000..b009280 --- /dev/null +++ b/lib/3/tag16_06_00002_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00003_geometry.csv b/lib/3/tag16_06_00003_geometry.csv new file mode 100644 index 0000000..bc7ef8c --- /dev/null +++ b/lib/3/tag16_06_00003_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00004_geometry.csv b/lib/3/tag16_06_00004_geometry.csv new file mode 100644 index 0000000..3726032 --- /dev/null +++ b/lib/3/tag16_06_00004_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00005_geometry.csv b/lib/3/tag16_06_00005_geometry.csv new file mode 100644 index 0000000..966ec48 --- /dev/null +++ b/lib/3/tag16_06_00005_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00006_geometry.csv b/lib/3/tag16_06_00006_geometry.csv new file mode 100644 index 0000000..ea66f5f --- /dev/null +++ b/lib/3/tag16_06_00006_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00007_geometry.csv b/lib/3/tag16_06_00007_geometry.csv new file mode 100644 index 0000000..e0964f1 --- /dev/null +++ b/lib/3/tag16_06_00007_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/3/tag16_06_00008_geometry.csv b/lib/3/tag16_06_00008_geometry.csv new file mode 100644 index 0000000..6e06823 --- /dev/null +++ b/lib/3/tag16_06_00008_geometry.csv @@ -0,0 +1,4 @@ +0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,-0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875,0.009875 +-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0757083333333335,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0691250000000001,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0625416666666668,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0559583333333335,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0493750000000001,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0427916666666668,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0362083333333335,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0296250000000001,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0230416666666668,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.0164583333333335,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00987500000000015,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,-0.00329166666666682,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00329166666666653,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.00987499999999986,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0164583333333332,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0230416666666665,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0296249999999999,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0362083333333332,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0427916666666665,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0493749999999999,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0559583333333332,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0625416666666665,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0691249999999999,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332,0.0757083333333332 +-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334,-0.0757083333333332,-0.0691249999999999,-0.0625416666666666,-0.0559583333333332,-0.0493749999999999,-0.0427916666666666,-0.0362083333333332,-0.0296249999999999,-0.0230416666666666,-0.0164583333333332,-0.00987499999999988,-0.00329166666666655,0.00329166666666679,0.00987500000000012,0.0164583333333334,0.0230416666666668,0.0296250000000001,0.0362083333333335,0.0427916666666668,0.0493750000000001,0.0559583333333335,0.0625416666666668,0.0691250000000001,0.0757083333333334 +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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,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,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,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 diff --git a/lib/note.txt b/lib/note.txt new file mode 100644 index 0000000..0f4d2e4 --- /dev/null +++ b/lib/note.txt @@ -0,0 +1,5 @@ +0: 0.61 m +1: 0.81 m +2: 1.22 m +3: 0.16 m + diff --git a/matlab/CCW1.mat b/matlab/CCW1.mat new file mode 100644 index 0000000..82215f5 Binary files /dev/null and b/matlab/CCW1.mat differ diff --git a/matlab/analyzeLiDARTagPackage.m b/matlab/analyzeLiDARTagPackage.m new file mode 100644 index 0000000..edf7c16 --- /dev/null +++ b/matlab/analyzeLiDARTagPackage.m @@ -0,0 +1,105 @@ +function out_t = analyzeLiDARTagPackage(input_t, path_folder) + delimiterIn = ','; + headerlinesIn = 1; + + if isempty(input_t) + index = strfind(path_folder, '/'); + char_name = char(path_folder); + input_t.name = char_name(index(end-1)+1:index(end)-1); + end + out_t = input_t; + out_t.num_data = []; + out_t.computation_mean = []; + out_t.timing_mean = []; + out_t.computation_hz = []; + out_t.timing_hz = []; + out_t.clusters = []; + + %% Computation time + name = "timing_computation_only.txt"; + filename = path_folder + name; + + data = importdata(filename, delimiterIn, headerlinesIn); + + % start from 2 to skip the first column + for k = 2:size(data.data, 2) + % timing.(genvarname(data.colheaders{1, k})) = data.data(:, k); + computation_mean.(genvarname(string(data.colheaders{1, k}) + ... + "_mean")) = mean(data.data(:, k)); + computation_hz.(genvarname(string(data.colheaders{1, k}) + ... + "_Hz")) = 1000/mean(data.data(:, k)); + end + out_t.computation_mean = computation_mean; + + % struct2table(computation_mean) + + + %% Timings + % name = "computation_time.txt"; + name = "timing_all.txt"; + filename = path_folder + name; + if ~isfile(filename) +% warning("No such file: %s", filename) + timing_mean = []; + timing_hz = []; + else + data = importdata(filename, delimiterIn, headerlinesIn); + + for k = 2:size(data.data, 2) + % timing.(genvarname(data.colheaders{1, k})) = data.data(:, k); + timing_mean.(genvarname(string(data.colheaders{1, k}) + ... + "_mean")) = mean(data.data(:, k)); + timing_hz.(genvarname(string(data.colheaders{1, k}) + ... + "_Hz")) = 1000/mean(data.data(:, k)); + end + end + + % struct2table(timing_mean) + + + + %% Clusters + % name = "computation_time.txt"; + name = "stats.txt"; + filename = path_folder + name; + if ~isfile(filename) + error("No such file: %s", filename) + end + data = importdata(filename, delimiterIn, headerlinesIn); + + for k = 2:size(data.data, 2) + % records.(genvarname(data.colheaders{1, k})) = data.data(:, k); + clusters.(genvarname(string(data.colheaders{1, k}) + ... + "_mean")) = mean(data.data(:, k)); + end + + + %% preparing for output_t + out_t.num_data = size(data.data, 1); + out_t.computation_mean = computation_mean; + out_t.computation_hz = computation_hz; + + out_t.timing_mean = timing_mean; + out_t.timing_hz = timing_hz; + + out_t.decoding_mean = []; + out_t.decoding_hz = []; + + out_t.clusters = clusters; + + %% Decoding + name = "decoding_analysis.txt"; + filename = path_folder + name; + if isfile(filename) + data = importdata(filename, delimiterIn, headerlinesIn); + for k = 2:size(data.data, 2) + decoding_hz.(genvarname(string(data.colheaders{1, k}) + ... + "_Hz")) = 1e3/mean(data.data(:, k)); + decoding_mean.(genvarname(string(data.colheaders{1, k}) + ... + "_mean")) = mean(data.data(:, k)); + end + out_t.decoding_hz = decoding_hz; + out_t.decoding_mean = decoding_mean; + end + +end \ No newline at end of file diff --git a/matlab/ccmain.m b/matlab/ccmain.m new file mode 100644 index 0000000..540fddc --- /dev/null +++ b/matlab/ccmain.m @@ -0,0 +1,408 @@ +clear, clc +% addpath(genpath("E:/2020summer_research/matlab/matlab_utils-master")); +% addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + +analyze_package = 0; % analyze each step of the pipeline +% event = 4; % which date +dataset = 2; % 1: front 2: ccw +tag_size = 1.22; + + +%% Which date and which datasets +switch dataset + case 1 + event_name_1 = "Oct11-2020/"; + prefix = "front"; + % right, bottom, left, top + mocap_corners_1 = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order_1 = [2, 3, 4, 1]; + + event_name_2 = "Oct07-2020/"; + mocap_corners_2 = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + % top, right, bottom, left + corner_order_2 = [1, 2, 3, 4]; + case 2 + event_name_1 = "Oct13-2020/"; + prefix = "ccw1-"; + corner_order_1 = [2, 3, 4, 1]; + % right, bottom, left, top + mocap_corners_1 = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + event_name_2 = "Oct07-2020/"; + mocap_corners_2 = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + % top, right, bottom, left + corner_order_2 = [1, 2, 3, 4]; +end +%% Path +root_path = "./paper_data/"; +lidar_path_1 = root_path + "gt_lidar/" + event_name_1; +lt_estimate_path_1 = root_path + "lidartag_estimates/" + event_name_1; +lidar_path_2 = root_path + "gt_lidar/" + event_name_2; +lt_estimate_path_2 = root_path + "lidartag_estimates/" + event_name_2; +% camera_path = root_path + "gt_camera/" + event_name; +lt_estimate_folers_1 = dir(lt_estimate_path_1 + prefix + "*"); +num_estimates_1 = size(lt_estimate_folers_1, 1); +lt_estimate_folers_2 = dir(lt_estimate_path_1 + prefix + "*"); +num_estimates_2 = size(lt_estimate_folers_2, 1); + + +%% Load data from txt files (ground truth data) +lidar_files = dir(lidar_path_1 + prefix + "*.txt"); +num_lidar_files = length(lidar_files); +% camera_files = dir(camera_path + prefix + "*.txt"); +% num_camera_files = length(camera_files); +% num_data = min(num_lidar_files, num_camera_files); +num_data = num_lidar_files; + +ground_truth(7) = struct(); +for i = 1:5 + % find idar file in camera files + ground_truth(i).lidar_file = lidar_files(i).name; +% index = find(strcmp({camera_files.name}, ... +% ground_truth(i).lidar_file)==1); + + ground_truth(i).name = ... + ground_truth(i).lidar_file(... + 1:strfind(ground_truth(i).lidar_file, '.') - 1); + + % load lidar data + lidar_data = ... + mean(dlmread(lidar_path_1 + lidar_files(i).name, ',', 1, 0)); + ground_truth(i).lidar_corners = ... + [lidar_data(2:4)', lidar_data(5:7)', ... + lidar_data(8:10)', lidar_data(11:13)']; + +% % load camera data +% ground_truth(i).camera_file = camera_files(index).name; +% camera_data = ... +% mean(dlmread(camera_path + ... +% ground_truth(i).camera_file, ',', 1, 0)); +% ground_truth(i).camera_corners = ... +% [camera_data(2:4)', camera_data(5:7)', ... +% camera_data(8:10)', camera_data(11:13)']; +% +% % assert if names are not the same +% assert(... +% strcmp(ground_truth(i).camera_file, ... +% ground_truth(i).lidar_file), "files mismatch") + + + out_t = computePoseFromLiDARToMocapMarkers(... + ground_truth(i).lidar_corners, mocap_corners_1, tag_size, corner_order_1); + + for fn = fieldnames(out_t)' + ground_truth(i).(fn{1}) = out_t.(fn{1}); + end +end + +switch dataset + case 1 + for i = 6:7 + lidar_files = dir(lidar_path_2 + prefix + "*.txt"); + ground_truth(i).lidar_file = lidar_files(i-1).name; + % index = find(strcmp({camera_files.name}, ... + % ground_truth(i).lidar_file)==1); + + ground_truth(i).name = ... + ground_truth(i).lidar_file(... + 1:strfind(ground_truth(i).lidar_file, '.') - 1); + + % load lidar data + lidar_data = ... + mean(dlmread(lidar_path_2 + lidar_files(i-1).name, ',', 1, 0)); + ground_truth(i).lidar_corners = ... + [lidar_data(2:4)', lidar_data(5:7)', ... + lidar_data(8:10)', lidar_data(11:13)']; + out_t = computePoseFromLiDARToMocapMarkers(... + ground_truth(i).lidar_corners, mocap_corners_2, tag_size, corner_order_2); + + for fn = fieldnames(out_t)' + ground_truth(i).(fn{1}) = out_t.(fn{1}); + end + end + case 2 + for i = 6:7 + lidar_files = dir(lidar_path_2 + prefix + "*.txt"); + ground_truth(i).lidar_file = lidar_files(i-2).name; + % index = find(strcmp({camera_files.name}, ... + % ground_truth(i).lidar_file)==1); + + ground_truth(i).name = ... + ground_truth(i).lidar_file(... + 1:strfind(ground_truth(i).lidar_file, '.') - 1); + + % load lidar data + lidar_data = ... + mean(dlmread(lidar_path_2 + lidar_files(i-2).name, ',', 1, 0)); + ground_truth(i).lidar_corners = ... + [lidar_data(2:4)', lidar_data(5:7)', ... + lidar_data(8:10)', lidar_data(11:13)']; + out_t = computePoseFromLiDARToMocapMarkers(... + ground_truth(i).lidar_corners, mocap_corners_2, tag_size, corner_order_2); + + for fn = fieldnames(out_t)' + ground_truth(i).(fn{1}) = out_t.(fn{1}); + end + end +end + +%% Load estimated LiDARTag pose/ID information +lidartag(length(7)) = struct('name', [], 'pose_file', [],... + 'pose_raw_data', [], 'iter', [], ... + 'id', [], 'rot_num', [], 'rotm', [], 'translation', [], ... + 'L_H_LT', [], 'rpy', [], ... + 'num_data', [], 'computation_hz', [], 'computation_mean', [],... + 'decoding_hz', [], 'decoding_mean', [], ... + 'timing_hz', [], 'timing_mean', [], 'clusters', []); +for i = 1:5 + lidartag(i).name = prefix + num2str(i); + lt_current_path = lt_estimate_path_1 + lidartag(i).name + "/"; + lidartag(i).pose_file = dir(lt_current_path + "*1.2*pose.txt"); + + if isempty(lidartag(i).pose_file) + continue + end + + % pose data + lidartag(i).pose_raw_data = dlmread(... + lt_current_path + lidartag(i).pose_file.name, ',', 1, 0); + + lidartag(i).iter = lidartag(i).pose_raw_data(:, 1); + lidartag(i).id = lidartag(i).pose_raw_data(:, 2); + lidartag(i).rot_num = lidartag(i).pose_raw_data(:, 3); + [lidartag(i).rotm, lidartag(i).translation] = ... + computeMeanOfTranslationNRotation(... + lidartag(i).pose_raw_data(:, 7:end), ... + lidartag(i).pose_raw_data(:, 4:6)); + lidartag(i).L_H_LT = eye(4); + lidartag(i).L_H_LT(1:3, 1:3) = lidartag(i).rotm; + lidartag(i).L_H_LT(1:3, 4) = lidartag(i).translation; + lidartag(i).rpy = ... + rad2deg(rotm2eul(lidartag(i).L_H_LT(1:3, 1:3), 'XYZ')); + + if analyze_package + lidartag(i) = analyzeLiDARTagPackage(lidartag(i), lt_current_path); + else + lidartag(i).num_data = size(lidartag(i).pose_raw_data, 1); + end +end +for i = 6:7 + lidartag(i).name = prefix + num2str(i); + lt_current_path = lt_estimate_path_2 + lidartag(i).name + "/"; + lidartag(i).pose_file = dir(lt_current_path + "*1.2*pose.txt"); + + + % pose data + lidartag(i).pose_raw_data = dlmread(... + lt_current_path + lidartag(i).pose_file.name, ',', 1, 0); + + lidartag(i).iter = lidartag(i).pose_raw_data(:, 1); + lidartag(i).id = lidartag(i).pose_raw_data(:, 2); + lidartag(i).rot_num = lidartag(i).pose_raw_data(:, 3); + [lidartag(i).rotm, lidartag(i).translation] = ... + computeMeanOfTranslationNRotation(... + lidartag(i).pose_raw_data(:, 7:end), ... + lidartag(i).pose_raw_data(:, 4:6)); + lidartag(i).L_H_LT = eye(4); + lidartag(i).L_H_LT(1:3, 1:3) = lidartag(i).rotm; + lidartag(i).L_H_LT(1:3, 4) = lidartag(i).translation; + lidartag(i).rpy = ... + rad2deg(rotm2eul(lidartag(i).L_H_LT(1:3, 1:3), 'XYZ')); + + if analyze_package + lidartag(i) = analyzeLiDARTagPackage(lidartag(i), lt_current_path); + else + lidartag(i).num_data = size(lidartag(i).pose_raw_data, 1); + end +end + +%% Compare with ground truth +gt_ID = 0; +gt_rot_num = 3; +results(num_data) = struct('name', [], 'distance', [], 'num_scans', [], ... + 'ID_ratio', [], 'translation', [], 'geodesic', []); +for i = 1:7 + if (isempty(lidartag(i).pose_raw_data)) + continue; + end + + index = find(strcmp({ground_truth.name}, lidartag(i).name)==1); + if isempty(index) + continue; + end + + results(i).name = lidartag(i).name; + results(i).distance = norm(ground_truth(index).translation); + results(i).num_scans = lidartag(i).num_data; + results(i).ID = length(find(abs((lidartag(i).id - gt_ID)))); + results(i).rot_num = ... + length(find(abs((lidartag(i).rot_num - gt_rot_num)))); + + results(i).ID_ratio = results(i).ID / lidartag(i).num_data; + results(i).rot_num_ratio = ... + results(i).rot_num / lidartag(i).num_data; + + i; + % translation is in mm + results(i).translation = ... + (ground_truth(index).translation - lidartag(i).translation) * 1000; + results(i).translation = ... + norm((ground_truth(index).translation - lidartag(i).translation) * 1000); + + results(i).rpy = ... + ground_truth(index).rpy - lidartag(i).rpy + change_coordinate; + results(i).geodesic = rad2deg(norm(Log_SO3(eul2rotm(deg2rad(results(i).rpy), "XYZ")))); + results(i).dH = ground_truth(index).L_H_LT / lidartag(i).L_H_LT; +end + +disp("===============================================================") +disp("=========== Results of Decoding and Pose Estimation ===========") +disp("===============================================================") +results(all(cell2mat(arrayfun( @(x) structfun( @isempty, x), ... + results, 'UniformOutput', false)), 1)) = []; +struct2table(results) + +disp("===============================================================") +disp("=========== Summary of Decoding and Pose Estimation ===========") +disp("===============================================================") +disp("-- mean:") +fprintf("---- Number of scans: %.3f\n", mean([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", mean([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", mean([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) +disp("-- median:") +fprintf("---- Number of scans: %.3f\n", median([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", median([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", median([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) +disp("-- std:") +fprintf("---- Number of scans: %.3f\n", std([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", std([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", std([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) + +%% Package general analysis +if analyze_package + disp("===============================================================") + disp("================= Results of General Analysis =================") + disp("===============================================================") + for i = 1:num_estimates + dataset_num = i; + if isempty(lidartag(dataset_num).num_data) + warning("No results for %s", lidartag(dataset_num).name) + else + disp("-------------------------------------------------------") + fprintf("Each of below average over %i scans ", ... + lidartag(dataset_num).num_data) + fprintf("from %s dataset: \n", lidartag(dataset_num).name) + disp("-------------------------------------------------------") + struct2table(lidartag(dataset_num).computation_hz) + struct2table(lidartag(dataset_num).timing_hz) + struct2table(lidartag(dataset_num).clusters) + + if isempty(lidartag(dataset_num).decoding_hz) + warning("No decoding_hz for %s dataset", ... + lidartag(dataset_num).name) + else + struct2table(lidartag(dataset_num).decoding_hz) + end + end + end + + %% summary + disp("===============================================================") + disp("============= Summary Results of General Analysis =============") + disp("===============================================================") + + summary_t = summarizeGeneralAnalysis(lidartag, "hz"); + disp("-----------------------------------------------------------") + fprintf("Average Hz over all dadtasets with %i scans \n", ... + summary_t.total_scans) + disp("-----------------------------------------------------------") + + t1 = struct2table(summary_t.computation_hz) + t2 = struct2table(summary_t.timing_hz) + t3 = struct2table(summary_t.clusters) + + if isfield('decoding_hz', summary_t) + t4 = struct2table(summary_t.decoding_hz) + end + + + disp("-----------------------------------------------------------") + fprintf("Average ms over all dadtasets with %i scans \n", ... + summary_t.total_scans) + disp("-----------------------------------------------------------") + summary_t = summarizeGeneralAnalysis(lidartag, "mean"); + t1 = struct2table(summary_t.computation_mean) + t2 = struct2table(summary_t.timing_mean) + t3 = struct2table(summary_t.clusters) + if isfield('decoding_mean', summary_t) + t4 = struct2table(summary_t.decoding_mean) + end +end +% t5 = array2table(table2array(struct2table(summary_t.computation_hz)).'); +% t5.Properties.RowNames = t1.Properties.VariableNames; +% t5.Properties.VariableNames = "Hz"; +% t5 + + + + + +%% Plottings +% X = ground_truth(1).lidar_corners'; % n x 3 +% Y = mocap_corners'; % n x 3 +% [~, mocap_at_lidar, ~] = procrustes(X, Y, 'scaling', 0, 'reflection', 0); +% +% template = [0, 0, 0, 0; +% tag_size/2, -tag_size/2, -tag_size/2 ,tag_size/2; +% tag_size/2, tag_size/2, -tag_size/2, -tag_size/2]'; +% [d, ~, transform] = ... +% procrustes(mocap_at_lidar, template, 'scaling', 0, 'reflection', 0); +% H_ML = eye(4); +% H_ML(1:3, 1:3) = transform.T'; +% H_ML(1:3, 4) = transform.c(1, :)'; +% mocap_lidar = H_ML * convertToHomogeneousCoord(template'); +% +% +% +% [axes_h, fig_h] = createFigHandleWithNumber(2, 1, "pose", 1, 1); +% cur_axes = axes_h(1); +% h1 = scatter3(cur_axes, X(:, 1), X(:, 2), X(:, 3), 'ko'); +% h2 = scatter3(cur_axes, Y(:, 1), Y(:, 2), Y(:, 3), 'b.'); +% h3 = scatter3(cur_axes, ... +% mocap_at_lidar(:, 1), ... +% mocap_at_lidar(:, 2), ... +% mocap_at_lidar(:, 3), 'rx'); +% legend([h1, h2, h3], ... +% ["L_lidar_corners", "M_mocap_corners", "L_mocap_corners"]) +% plotColoredOriginAxisWithText(cur_axes, "LiDAR", eye(4), 0.5) +% showCurrentPlot(cur_axes, "Mocap to LiDAR", [-50, 30]) +% +% +% cur_axes = axes_h(2); +% scatter3(cur_axes, ... +% template(:, 1), template(:, 2), template(:, 3), ... +% 'fill', 'ko') +% scatter3(cur_axes, X(:, 1), X(:, 2), X(:, 3), 'bo') +% scatter3(cur_axes, ... +% mocap_lidar(1, :), mocap_lidar(2, :), mocap_lidar(3, :), 'r*') +% % scatter3(... +% cur_axes, mocap_lidar(:, 1), mocap_lidar(:, 2), mocap_lidar(:, 3), 'r*') +% plotColoredOriginAxisWithText(cur_axes, "LiDAR", eye(4), 0.5) +% showCurrentPlot(cur_axes, "LiDAR", [-70, 10]) \ No newline at end of file diff --git a/matlab/computeMeanOfTranslationNRotation.m b/matlab/computeMeanOfTranslationNRotation.m new file mode 100644 index 0000000..0ac55e1 --- /dev/null +++ b/matlab/computeMeanOfTranslationNRotation.m @@ -0,0 +1,17 @@ +function [r_mean, t_mean] = ... + computeMeanOfTranslationNRotation(rot_v, trans_v) + % rot_v: n x 9 + % trans_v: n x 3 + % rot_v is in the oder of r11, r12, r13, r21, r22, r23, r31, r32, r33 + + t_mean = mean(trans_v, 1); + num_rotation = size(rot_v, 1); + + ave = zeros(3, 1); + for i = 1:num_rotation + rotm = reshape(rot_v(i, :), [], 3)'; + ave = ave + Log_SO3(rotm); + end + ave = ave / num_rotation; + r_mean = Exp_SO3(ave); +end \ No newline at end of file diff --git a/matlab/computePoseFromLiDARToMocapMarkers.m b/matlab/computePoseFromLiDARToMocapMarkers.m new file mode 100644 index 0000000..f0270a7 --- /dev/null +++ b/matlab/computePoseFromLiDARToMocapMarkers.m @@ -0,0 +1,43 @@ +function out_t = ... + computePoseFromLiDARToMocapMarkers(L_X, M_Y, tag_size, corner_order) + % X: Target vertices estiamted from the lidar frame + % Y: Mocap makers measured from the mocap frame + % Assume X and Y are the same but measured from different sensors, + % Here, the sensors are mocap and lidar + + % Transform data from 3xn to nx3 + L_X = L_X'; % n x 3 + M_Y = M_Y'; % n x 3 + + % Construct template at the lidar origin + template = [0, 0, 0, 0; + tag_size/2, -tag_size/2, -tag_size/2 ,tag_size/2; + tag_size/2, tag_size/2, -tag_size/2, -tag_size/2]; + template = template(:, corner_order)'; + + + + % Estimate H from Y to X, which results in Y measured in LiDAR frame + [cost_ML, L_Y, ~] = procrustes(L_X, M_Y, 'scaling', 0, 'reflection', 0); + + + % Esimate the H from the template at the lidar origin to the markers at + % LiDAR frame (L_marker) + [cost_LT, ~, transform] = procrustes(L_Y, template, 'scaling', 0, 'reflection', 0); + + + % L_template_to_target and L_Y should be close to each other + H_ML = eye(4); + H_ML(1:3, 1:3) = transform.T'; + H_ML(1:3, 4) = transform.c(1, :)'; + L_template_to_target = H_ML * convertToHomogeneousCoord(template'); + + out_t.cost_ML = cost_ML; + out_t.cost_LT = cost_LT; + out_t.L_markers = L_Y; + out_t.L_template_to_target = L_template_to_target; + out_t.L_H_LT = H_ML; + out_t.translation = H_ML(1:3, 4)'; + out_t.rpy = rad2deg(rotm2eul(H_ML(1:3, 1:3), "XYZ")); + +end diff --git a/matlab/false_positives.m b/matlab/false_positives.m new file mode 100644 index 0000000..35679fa --- /dev/null +++ b/matlab/false_positives.m @@ -0,0 +1,30 @@ +clc, clear + +path = "./paper_data/public_datasets/"; +data_num = 3; + + +switch data_num + case 1 + dataset = "cartographer/horizontal_lidar"; + case 2 + dataset = "cartographer/vertical_lidar"; + case 3 + dataset = "H3D"; +end +path_folder = path + dataset + "/stats.txt"; +delimiterIn = ','; +headerlinesIn = 1; + + + +disp("===============================================================") +fprintf("=============== False Positives for %s dataset ===============\n", ... + dataset) +disp("===============================================================") +data.pose_raw_data = dlmread(path_folder, ',', 1, 0); +data.num_scan = size(data.pose_raw_data, 1); +false_positives_index = find(data.pose_raw_data(:, size(data.pose_raw_data, 2))); +data.pose_raw_data(false_positives_index, :); +data.false_positives = length(false_positives_index); +data.false_positives_ratio = length(false_positives_index)/data.num_scan * 100 \ No newline at end of file diff --git a/matlab/function_dictionary/build_LiDARTag_library.m b/matlab/function_dictionary/build_LiDARTag_library.m new file mode 100644 index 0000000..4fd3be4 --- /dev/null +++ b/matlab/function_dictionary/build_LiDARTag_library.m @@ -0,0 +1,105 @@ +%{ + * Copyright (C) 2013-2025, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang[at]umich.edu) + * WEBSITE: https://www.brucerobot.com/ +%} + +clc, clear +addpath(genpath("/home/brucebot/workspace/matlab_utils")); + + +poolobj = gcp('nocreate'); +% delete(poolobj) +if isempty(poolobj) + parpool('max-threading', 4); +end + +opts.verbose.output_level = 1; +opts.num_tag = 9; %5, 9, 30 % max is 30 for tag1606 +opts.img_path = "tag16h6/"; % tag_img/ +opts.img_prefix = "tag16_06_%05d.png"; + +%% Tag Family Setting +tag = loadAprilTagFamily(); + + + +%% ideal frame +opts.target_size = 0.61; % 0.158, 0.8051, 1.22 +opts.polygon = 4; +opts.rpy = [0, 0, 0]; +opts.xyz = [0, 0, 0]; +[ideal_object_list, ~] = createDynamicScene(opts); +LiDARTag.ideal_frame = convertXYZstructToXYZmatrix(ideal_object_list.object_vertices); +LiDARTag.ideal_object_list = ideal_object_list; + + + +opts.save_path = "./data_test/" + opts.img_path + num2str(opts.target_size) + "/"; +opts.load_path = "./data_test/" + opts.img_path + num2str(opts.target_size) + "/"; +checkDirectory(opts.save_path); + + +%% AprilTag +score_table_t(opts.num_tag) = struct(); +opts.ell = opts.target_size/tag.num_bit/2; + + +for img = 1:opts.num_tag + aptiltag_data_t = loadAprilTagPointCloud(opts, img); + score_table_t(img).image_name = aptiltag_data_t.image_name; + score_table_t(img).image_array = aptiltag_data_t.image_array; + score_table_t(img).geometry_img = aptiltag_data_t.geometry_img; +end + + +%% Plottings +tag_num = 5; +image_name = score_table_t(tag_num).image_name; +image_array = score_table_t(tag_num).image_array; +geometry_img = score_table_t(tag_num).geometry_img; + + +% Plottings +[axes_h, ~] = createFigHandleWithNumber(5, 1, "overlayAprilTag", 1, 1); +cur_axes = axes_h(1); +AprilTag_map = genColorMap(image_array(4,:), 10, 1); +scatter3(cur_axes, image_array(1,:), image_array(2,:), image_array(3,:), [], AprilTag_map, 'fill') +plotObjectsList(cur_axes, opts, [], LiDARTag.ideal_object_list) +plotOriginalAxisWithText(cur_axes, "LiDAR") +viewCurrentPlot(cur_axes, "Template with AprilTag", [-60 20], 1) +reloadCurrentPlot(cur_axes, 1) + + +cur_axes = axes_h(2); +scatter3(cur_axes, geometry_img(1,:), geometry_img(2,:), geometry_img(3,:), [], AprilTag_map, 'fill') +plotObjectsList(cur_axes, opts, [], LiDARTag.ideal_object_list) +plotOriginalAxisWithText(cur_axes, "LiDAR") +viewCurrentPlot(cur_axes, "Template with Geometry AprilTag", [-60 20], 1) +reloadCurrentPlot(cur_axes, 1) +disp("Library built") diff --git a/matlab/function_dictionary/compare_with_apriltag_dic.m b/matlab/function_dictionary/compare_with_apriltag_dic.m new file mode 100644 index 0000000..d1e518e --- /dev/null +++ b/matlab/function_dictionary/compare_with_apriltag_dic.m @@ -0,0 +1,116 @@ +%{ + * Copyright (C) 2013-2025, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang[at]umich.edu) + * WEBSITE: https://www.brucerobot.com/ +%} + +clc, clear + +% Tag Family Setting +tag = loadAprilTagFamily(); + +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +poolobj = gcp('nocreate'); +% delete(poolobj) +if isempty(poolobj) + parpool('max-threading', 4); +end +opts.verbose.output_level = 1; +opts.num_tag = 5; % max is 30 +opts.img_path = "tag16h6/"; % tag_img/ +opts.img_prefix = "tag16_06_%05d.png"; + + +%% Load lidartag data +dataset = 1; +[out_t, opts, opt] = loadData(opts, dataset); +lidartag_data_t = transformToTemplate(opt, opts, out_t.X); + +target_size = lidartag_data_t.target_size; +X_clean = lidartag_data_t.X_clean; +pionts_ideal_frame = lidartag_data_t.pionts_ideal_frame; +projected_vertices = lidartag_data_t.projected_vertices; + + +opts.save_path = "./data/" + opts.img_path + "/" + num2str(opts.target_size) + "/"; +opts.load_path = "./data/" + opts.img_path + "/" + num2str(opts.target_size) + "/"; +checkDirectory(opts.save_path); + +%% AprilTag +clc +score_table_t(opts.num_tag) = struct(); +opts.ell = lidartag_data_t.target_size/tag.num_bit/2; +parforProgress(opts.num_tag); +parfor img = 1:opts.num_tag + parforProgress; + + aptiltag_data_t = loadAprilTagPointCloud(opts, img); + inner_product_t = computeGeometryAndNormalInnerProduct(opts, lidartag_data_t, aptiltag_data_t); + + score_table_t(img).image_name = aptiltag_data_t.image_name; + score_table_t(img).image_array = aptiltag_data_t.image_array; + score_table_t(img).geometry_img = aptiltag_data_t.geometry_img; + score_table_t(img).geometry_pc = inner_product_t.geometry_pc; + score_table_t(img).inner_product = inner_product_t.inner_product; + score_table_t(img).geometry_inner_product = inner_product_t.geometry_inner_product; +end +parforProgress(0); + + +inner_product_vec = [score_table_t(:).inner_product] +fprintf("\n\n") +geo_inner_product_vec = [score_table_t(:).geometry_inner_product] + + + +fprintf("inner_product\n") +[value, indx] = max(inner_product_vec) + +fprintf("geometry_inner_product\n") +[geo_value, geo_indx] = max(geo_inner_product_vec) + + +fprintf("image name (normal): %s\n", score_table_t(indx).image_name) +fprintf("image name (geom): %s\n", score_table_t(geo_indx).image_name) +%% Plottings +tag_num = geo_indx; +image_name = score_table_t(tag_num).image_name; +image_array = score_table_t(tag_num).image_array; +geometry_img = score_table_t(tag_num).geometry_img; +geometry_pc = score_table_t(tag_num).geometry_pc; + + +% Plottings +plotResults(opts, image_array, out_t.ideal_object_list, out_t.X, ... + lidartag_data_t.X_clean, lidartag_data_t.pionts_ideal_frame, ... + lidartag_data_t.projected_vertices,... + geometry_img, geometry_pc) diff --git a/matlab/function_dictionary/computeFunctionInnerProduct.m b/matlab/function_dictionary/computeFunctionInnerProduct.m new file mode 100644 index 0000000..b9a926e --- /dev/null +++ b/matlab/function_dictionary/computeFunctionInnerProduct.m @@ -0,0 +1,29 @@ +function inner_product = computeFunctionInnerProduct(point_cloud1, point_cloud2, geo_ell) + if ~exist('geo_ell', 'var') + geo_ell = 0.05; % 0.05 + end + feature_ell = 10; + geo_sig = 1e5; + + num_piont1 = size(point_cloud1, 2); + num_piont2 = size(point_cloud2, 2); + inner_prod_A = zeros(num_piont1, num_piont2); + + + for i = 1:num_piont1 + feature1 = point_cloud1(4, i); + p1 = point_cloud1(1:3, i); + + for j = 1:num_piont2 + feature2 = point_cloud2(4, j); + p2 = point_cloud2(1:3, j); + + feature_kernel = exp( -(norm(feature1 - feature2)) / (2*feature_ell^2) ); + geometry_kernel = geo_sig * exp( -(norm(p1 - p2)) / (2*geo_ell^2) ); + + + inner_prod_A(i, j) = feature_kernel * geometry_kernel; + end + end + inner_product = sum(sum(inner_prod_A))/(num_piont1 * num_piont2); +end \ No newline at end of file diff --git a/matlab/function_dictionary/computeGeometryAndNormalInnerProduct.m b/matlab/function_dictionary/computeGeometryAndNormalInnerProduct.m new file mode 100644 index 0000000..6f88f3f --- /dev/null +++ b/matlab/function_dictionary/computeGeometryAndNormalInnerProduct.m @@ -0,0 +1,6 @@ +function out_t = computeGeometryAndNormalInnerProduct(opts, lidartag_data_t, aptiltag_data_t) + out_t.ell = opts.ell; + out_t.geometry_pc = constructGeometryPointCloud(lidartag_data_t.pionts_ideal_frame, out_t.ell); + out_t.inner_product = computeFunctionInnerProduct(lidartag_data_t.pionts_ideal_frame, aptiltag_data_t.image_array, out_t.ell); + out_t.geometry_inner_product = computeFunctionInnerProduct(out_t.geometry_pc, aptiltag_data_t.geometry_img, out_t.ell); +end \ No newline at end of file diff --git a/matlab/function_dictionary/constructGeometryPointCloud.m b/matlab/function_dictionary/constructGeometryPointCloud.m new file mode 100644 index 0000000..18b9185 --- /dev/null +++ b/matlab/function_dictionary/constructGeometryPointCloud.m @@ -0,0 +1,23 @@ +function geometry_pc = constructGeometryPointCloud(point_cloud, separation) + if ~exist('separation', 'var') + separation = 0.1; + end + average_intensity = mean(point_cloud(4,:)); + offset_intensity = point_cloud(4,:) - average_intensity; + + pos_ind = offset_intensity>=0; + pos_intensity = offset_intensity(pos_ind); + pos_threshold = median(pos_intensity); + pos_intensity = pos_intensity/abs(pos_threshold); + + neg_ind = offset_intensity<0; + neg_intensity = offset_intensity(neg_ind); + neg_threshold = median(neg_intensity); + neg_intensity = neg_intensity/abs(neg_threshold); + + offset_intensity(pos_ind) = separation * pos_intensity; + offset_intensity(neg_ind) = separation * neg_intensity; +% offset_intensity = offset_intensity/threshold; + geometry_pc = point_cloud; + geometry_pc(1,:) = offset_intensity; +end \ No newline at end of file diff --git a/matlab/function_dictionary/loadAprilTagFamily.m b/matlab/function_dictionary/loadAprilTagFamily.m new file mode 100644 index 0000000..e2ea5f4 --- /dev/null +++ b/matlab/function_dictionary/loadAprilTagFamily.m @@ -0,0 +1,8 @@ +function tag = loadAprilTagFamily() + tag.family = 4; % LiDARTag family + tag.black_border = 1; + tag.white_border = 1; + tag.grid_size = 0.5; % size of each grid + tag.num_bit = tag.family + 2*tag.black_border + 2*tag.white_border; % bit on a side + tag.size = tag.grid_size * tag.num_bit; +end \ No newline at end of file diff --git a/matlab/function_dictionary/loadAprilTagPointCloud.m b/matlab/function_dictionary/loadAprilTagPointCloud.m new file mode 100644 index 0000000..181f6fe --- /dev/null +++ b/matlab/function_dictionary/loadAprilTagPointCloud.m @@ -0,0 +1,84 @@ +function out_t = loadAprilTagPointCloud(opts, tag_num) + if ~isfield(opts, 'file_type') + opts.file_type = ".csv"; + end + + if ~isfield(opts, 'num_tag') + opts.num_tag = 30; + end + if ~isfield(opts, 'rotation') + opts.rotation = -90; + end + if ~isfield(opts, 'v_flip') + opts.v_flip = 0; + end + img_path = opts.img_path; + img_ary = num2str([0:opts.num_tag-1].',opts.img_prefix); +% name_image_array = + + + cur_img = img_ary(tag_num ,:); + img_name = string(cur_img(1:strfind(cur_img,'.')-1)) + "_planer" + opts.file_type; + img_geo_name = string(cur_img(1:strfind(cur_img,'.')-1)) + "_geometry" + opts.file_type; + + % image point cloud + if isfile(opts.load_path + img_name) + if opts.file_type == ".csv" + image_array = load(opts.load_path + img_name); + else + load(opts.load_path + img_name); + end + + displayMessages(opts, img_name + " loaded", 3); + else + img_dict = imread(img_path + cur_img); % Load LiDARTag + if opts.v_flip + img_dict = flip(img_dict, 2); % horizontal flip + end + img_dict = imrotate(img_dict, opts.rotation); + img_dict = rgb2gray(img_dict)./255; + [img_dict] = imresize(img_dict, 3, 'nearest'); + scale_ratio = size(img_dict)/opts.target_size; + + image_array = zeros(4, size(img_dict, 1)*size(img_dict, 2)); + counter = 1; + for i = 1:size(img_dict, 1) + for j = 1:size(img_dict, 2) + current_intensity = img_dict(i, j); + point = [0; double(i/scale_ratio(1)); double(j/scale_ratio(2)); double(current_intensity)]; + image_array(:, counter) = point; + counter = counter + 1; + end + end + image_array_mean = mean(image_array(1:3,:), 2); + image_array(1:3, :) = image_array(1:3, :) - image_array_mean; + + if opts.file_type == ".csv" + writematrix(image_array, opts.save_path + img_name, 'Delimiter', ',') + else + save(opts.save_path + img_name, 'image_array'); + end + displayMessages(opts, img_name + " saved", 3); + end + + if isfile(opts.load_path + img_geo_name) + if opts.file_type == ".csv" + geometry_img = load(opts.load_path + img_geo_name); + else + load(opts.load_path + img_geo_name); + end + displayMessages(opts, img_geo_name + " loaded", 3); + else + geometry_img = constructGeometryPointCloud(image_array, opts.ell); + + if opts.file_type == ".csv" + writematrix(geometry_img, opts.save_path + img_geo_name, 'Delimiter', ',') + else + save(opts.save_path + geometry_img, 'geometry_img'); + end + displayMessages(opts, img_geo_name + " saved", 3); + end + out_t.image_name = cur_img; + out_t.image_array = image_array; + out_t.geometry_img = geometry_img; +end \ No newline at end of file diff --git a/matlab/function_dictionary/loadData.m b/matlab/function_dictionary/loadData.m new file mode 100644 index 0000000..2caff1f --- /dev/null +++ b/matlab/function_dictionary/loadData.m @@ -0,0 +1,53 @@ +function [out_t, opts, opt] = loadData(opts, dataset) + path = "./test_mats/"; + if dataset==1 + name = "velodyne_points-lab3-closer-big--2019-09-06-08-38.mat"; + opts.target_size = 0.8051; + opts.rotation = -90; +% opts.rotation = 0; + opts.v_flip = 0; + elseif dataset==2 + name = "velodyne_points-lab4-closer-big--2019-09-06-13-49.mat"; + opts.target_size = 0.8051; + opts.rotation = -90; + opts.v_flip = 1; + elseif dataset==3 + name = "velodyne_points-lab5-closer-bag--2019-09-06-14-27.mat"; + opts.target_size = 0.8051; + opts.rotation = 180; + opts.v_flip = 1; + elseif dataset==4 + name = "velodyne_points-lab6-closer-big--2019-09-06-15-09.mat"; + opts.target_size = 0.8051; + opts.rotation = 0; + opts.v_flip = 0; + elseif dataset==5 + name = "velodyne_points-lab7-closer-big--2019-09-06-15-14.mat"; + opts.target_size = 0.8051; + opts.rotation = 0; + opts.v_flip = 0; + elseif dataset==6 + name = "velodyne_points-lab8-closer-big--2019-09-06-15-28.mat"; + opts.target_size = 0.8051; + opts.rotation = 0; + opts.v_flip = 0; + elseif dataset==7 + name = "velodyne_points-lab3-closer-small--2019-09-06-08-35.mat"; + opts.target_size = 0.158; + opts.target_size = 0.16; + end + pc = loadPointCloud(path, name); + out_t.X = getPayloadWithIntensity(pc, 1, 1); + out_t.X(4, :) = out_t.X(4, :)./255; + + std_noise = estimatePlanarNoise(out_t.X); + opts.box_width = 2*std_noise(3); + + % ideal frame + opts.polygon = 4; + opts.rpy = [0, 0, 0]; + opts.xyz = [0, 0, 0]; + [ideal_object_list, ~] = createDynamicScene(opts); + opt.ideal_frame = convertXYZstructToXYZmatrix(ideal_object_list.object_vertices); + out_t.ideal_object_list = ideal_object_list; +end \ No newline at end of file diff --git a/matlab/function_dictionary/plotResults.m b/matlab/function_dictionary/plotResults.m new file mode 100644 index 0000000..ff4da8c --- /dev/null +++ b/matlab/function_dictionary/plotResults.m @@ -0,0 +1,42 @@ +function plotResults(opts, image_array, ideal_object_list, ... + X, X_clean, pionts_ideal_frame, projected_vertices,... + geometry_img, geometry_pc) + [axes_h, ~] = createFigHandleWithNumber(5, 1, "overlayAprilTag", 1, 1); + cur_axes = axes_h(1); + AprilTag_map = genColorMap(image_array(4,:), 10, 1); + scatter3(cur_axes, image_array(1,:), image_array(2,:), image_array(3,:), [], AprilTag_map, 'fill') + plotObjectsList(cur_axes, opts, [], ideal_object_list) + plotOriginalAxisWithText(cur_axes, "LiDAR") + LiDARTag_map = genColorMap(X(4,:), 10, 1); + scatter3(cur_axes, X(1,:), X(2,:), X(3,:), [], LiDARTag_map, 'fill') + viewCurrentPlot(cur_axes, "Ideal LiDARTag with AprilTag", [-60 20], 1) + reloadCurrentPlot(cur_axes, 1) + + cur_axes = axes_h(2); + scatter3(cur_axes, X(1,:), X(2,:), X(3,:), [], 'fill', 'go') + clean_LiDARTag_map = genColorMap(X_clean(4, :), 10, 1); + scatter3(cur_axes, X_clean(1,:), X_clean(2,:), X_clean(3,:), [], clean_LiDARTag_map, 'fill') + scatter3(cur_axes, pionts_ideal_frame(1,:), pionts_ideal_frame(2,:), pionts_ideal_frame(3,:), [], clean_LiDARTag_map, 'fill') + scatter3(cur_axes, projected_vertices(1,:), projected_vertices(2,:), projected_vertices(3,:), 'fill', 'ro') + plotObjectsList(cur_axes, opts, [], ideal_object_list) + viewCurrentPlot(cur_axes, "Cleaned LiDARTag", [-70 10], 1) + + + + cur_axes = axes_h(3); + scatter3(cur_axes, geometry_img(1,:), geometry_img(2,:), geometry_img(3,:), [], AprilTag_map, 'fill') + plotObjectsList(cur_axes, opts, [], ideal_object_list) + plotOriginalAxisWithText(cur_axes, "LiDAR") + LiDARTag_map = genColorMap(X(4,:), 10, 1); + scatter3(cur_axes, X(1,:), X(2,:), X(3,:), [], LiDARTag_map, 'fill') + viewCurrentPlot(cur_axes, "Geometry AprilTag", [-60 20], 1) + reloadCurrentPlot(cur_axes, 1) + + cur_axes = axes_h(4); + scatter3(cur_axes, X(1,:), X(2,:), X(3,:), [], 'fill', 'go') + scatter3(cur_axes, X_clean(1,:), X_clean(2,:), X_clean(3,:), [], clean_LiDARTag_map, 'fill') + scatter3(cur_axes, geometry_pc(1,:), geometry_pc(2,:), geometry_pc(3,:), [], clean_LiDARTag_map, 'fill') + scatter3(cur_axes, projected_vertices(1,:), projected_vertices(2,:), projected_vertices(3,:), 'fill', 'ro') + plotObjectsList(cur_axes, opts, [], ideal_object_list) + viewCurrentPlot(cur_axes, "Geometry LiDARTag", [-70 10], 1) +end \ No newline at end of file diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00000.png b/matlab/function_dictionary/tag16h6/tag16_06_00000.png new file mode 100644 index 0000000..fc8fed2 Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00000.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00001.png b/matlab/function_dictionary/tag16h6/tag16_06_00001.png new file mode 100644 index 0000000..68a733d Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00001.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00002.png b/matlab/function_dictionary/tag16h6/tag16_06_00002.png new file mode 100644 index 0000000..6137081 Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00002.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00003.png b/matlab/function_dictionary/tag16h6/tag16_06_00003.png new file mode 100644 index 0000000..19d806d Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00003.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00004.png b/matlab/function_dictionary/tag16h6/tag16_06_00004.png new file mode 100644 index 0000000..886f8c5 Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00004.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00005.png b/matlab/function_dictionary/tag16h6/tag16_06_00005.png new file mode 100644 index 0000000..a9289db Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00005.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00006.png b/matlab/function_dictionary/tag16h6/tag16_06_00006.png new file mode 100644 index 0000000..f8a8267 Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00006.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00007.png b/matlab/function_dictionary/tag16h6/tag16_06_00007.png new file mode 100644 index 0000000..499b58a Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00007.png differ diff --git a/matlab/function_dictionary/tag16h6/tag16_06_00008.png b/matlab/function_dictionary/tag16h6/tag16_06_00008.png new file mode 100644 index 0000000..6e2b7f2 Binary files /dev/null and b/matlab/function_dictionary/tag16h6/tag16_06_00008.png differ diff --git a/matlab/function_dictionary/test_function_inner_product.m b/matlab/function_dictionary/test_function_inner_product.m new file mode 100644 index 0000000..00be9b7 --- /dev/null +++ b/matlab/function_dictionary/test_function_inner_product.m @@ -0,0 +1,265 @@ +%{ + * Copyright (C) 2013-2025, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang[at]umich.edu) + * WEBSITE: https://www.brucerobot.com/ +%} +clc, clear + +% Tag Family Setting +tag = loadAprilTagFamily(); + +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +poolobj = gcp('nocreate'); +% delete(poolobj) +if isempty(poolobj) + parpool('max-threading', 4); +end + + +opts.verbose.output_level = 1; +opts.num_tag = 5; % max is 30 +opts.img_path = "tag16h6/"; % tag_img/ +opts.img_prefix = "tag16_06_%05d.png"; + + +%% Load lidartag data +dataset = 1; +[out_t, opts, opt] = loadData(opts, dataset); +lidartag_data_t = transformToTemplate(opt, opts, out_t.X); + +target_size = lidartag_data_t.target_size; +X_clean = lidartag_data_t.X_clean; +pionts_ideal_frame = lidartag_data_t.pionts_ideal_frame; +projected_vertices = lidartag_data_t.projected_vertices; + + +opts.save_path = "./data/" + opts.img_path + "/" + num2str(opts.target_size) + "/"; +opts.load_path = "./data/" + opts.img_path + "/" + num2str(opts.target_size) + "/"; +checkDirectory(opts.save_path); +%% AprilTag +tag_number = 1; +opts.ell = lidartag_data_t.target_size/tag.num_bit/2; +aptiltag_data_t = loadAprilTagPointCloud(opts, tag_number); +inner_product_t = computeGeometryAndNormalInnerProduct(opts, lidartag_data_t, aptiltag_data_t); +fprintf("normal inner product: %3f\n", inner_product_t.inner_product) +fprintf("geometry inner product: %3f\n", inner_product_t.geometry_inner_product) + +% Plottings +plotResults(opts, aptiltag_data_t.image_array, out_t.ideal_object_list, out_t.X, ... + lidartag_data_t.X_clean, lidartag_data_t.pionts_ideal_frame, ... + lidartag_data_t. projected_vertices,... + aptiltag_data_t.geometry_img, inner_product_t.geometry_pc) + +disp("All done") + + + + + + + + +% infernce_old = -1; +% for infernce = 0:num_tag +% for target = 0:num_tag +% % img_inference = imread(img_ary(target,:)); % Load LiDARTag +% % +% % img_dict = imread(img_ary(infernce,:)); % Load LiDARTag +% img_dict = imread(img_path + sprintf("tag16_05_%05d.png", target)); % Load LiDARTag +% img_inference = imread(img_path + sprintf("tag16_05_%05d.png", infernce)); % Load LiDARTag +% fprintf("------\n -- Working on \n --- Target: %s \n --- Inference: %s \n------\n", ... +% sprintf("tag16_05_%05d.png", target), sprintf("tag16_05_%05d.png", infernce)) +% score_table.Properties.VariableNames(target+1) = "tag" + num2str(target); +% score_table.Properties.RowNames(infernce+1) = "tag" + num2str(infernce); +% +% % Show Image in 3D +% if plotting.plot_figure +% figure(1) +% gcf = figure(1); +% set(gcf,'name', sprintf("tag16_05_%05d.png", target)); +% img_x = -plotting.img_x: plotting.grid_size : plotting.img_x; +% img_y = -plotting.img_y: plotting.grid_size : plotting.img_y; +% image(img_x(:), img_y(:), img_dict, 'AlphaData', 0.5); +% hold on; +% end +% +% +% %% Construct Tag Image Gaussian Distribution +% disp("Constructing tag image Gaussian distribution...") +% sigma = [tag.grid_size/5 0; 0 tag.grid_size/5]; +% peak = 1; +% [tag.img.distribution, tag.img.normalized_distribution] = genTagImageDistribution(img_dict, tag.grid_size, plotting, peak, sigma); +% % max(tag.img.normalized_distribution, [], 'all') +% % min(tag.img.normalized_distribution, [], 'all') +% tag.img.distribution = tag.img.distribution + plotting.height; +% tag.img.normalized_distribution = tag.img.normalized_distribution + plotting.height; +% +% % surf(plotting.plot_x, plotting.plot_y, tag.img.distribution, 'AlphaData', 0.1,'FaceAlpha', 0.5) +% if plotting.plot_figure +% surf(plotting.plot_x, plotting.plot_y, tag.img.normalized_distribution, 'AlphaData', 0.1,'FaceAlpha', 0.5) +% +% +% % Figure Setting +% % view(-30,40) +% view(0,45) +% view(90,70) +% view(180,-90) +% view(25,30) +% % caxis([min(y(:))-0.5*range(y(:)),max(y(:))]) +% % axis([-3 3 -3 3 0 0.4]) +% % xlabel('x') +% % ylabel('y') +% % zlabel('Probability Density') +% axis equal +% fig = gcf; +% set(fig, 'Color', 'None') +% hold off +% end +% +% +% %% LiDAR points simulation with intensities +% if infernce_old ~= infernce +% disp("Constructing LiDARTag frame and xyz points...") +% tag = genFrameCoordinate(tag); % LiDARTag frame +% tag = genLiDARTagPoints(tag); % LiDARTag xyz-points +% +% % LiDAR Intensity +% disp("Constructing intensity of LiDARTag points...") +% vec1 = [0 -1 0]; +% vec2 = [0 0 -1]; +% corner = [0 -2 -2]; +% use_binary = 0; +% tag.sim.noisy.points = genPointIntensityBasedOnImageTag(corner, vec1, vec2, img_inference, peak, tag.num_bit, tag.grid_size, tag.sim.noisy.points, use_binary); +% +% % Show results +% if plotting.plot_figure +% disp('Drawing constructed results...') +% figure(2) +% gcf = figure(2); +% set(gcf,'name', sprintf("tag16_05_%05d.png", infernce)); +% ptCloud = pointCloud([tag.sim.noisy.points.x; tag.sim.noisy.points.y; tag.sim.noisy.points.z]', 'Intensity', tag.sim.noisy.points.normalized_intensity'); +% pcshow(ptCloud) +% hold off +% +% figure(3) +% gcf = figure(3); +% set(gcf,'name', sprintf("tag16_05_%05d.png", infernce)); +% for i = 1:size(tag.sim.noisy.points.x, 2) +% scatter3(tag.sim.noisy.points.x(i), tag.sim.noisy.points.y(i), tag.sim.noisy.points.z(i), 'or', 'MarkerFaceColor', 'k', 'MarkerFaceAlpha', tag.sim.noisy.points.plotting.normalized_intensity(i)) +% hold on +% end +% scatter3(tag.sim.noise_free.points.x, tag.sim.noise_free.points.y, tag.sim.noise_free.points.z, '.b') +% scatter3(tag.scatter3.x, tag.scatter3.y, tag.scatter3.z, 'ok') +% plot3(reshape(tag.plot3.x,2,[]),reshape(tag.plot3.y,2,[]), reshape(tag.plot3.z,2,[]), 'k') +% axis equal +% xlabel('x') +% ylabel('y') +% zlabel('z') +% hold off +% end +% +% %% Create LiDAR point distributions +% disp('Constructing LiDARTag point distributions...') +% tag.sim.noisy.points = genLiDARPointsDistribution(plotting, peak, sigma, tag.sim.noisy.points); +% +% % Show results +% if plotting.plot_figure +% disp('Drawing constructed results...') +% figure(4) +% gcf = figure(4); +% set(gcf,'name', sprintf("tag16_05_%05d.png", infernce)); +% image(img_x(:), img_y(:), img_inference, 'AlphaData', 0.5); +% hold on +% surf(plotting.plot_x, plotting.plot_y, tag.sim.noisy.points.normalized_distribution, 'AlphaData', 0.1,'FaceAlpha', 0.5) +% axis equal +% xlabel('x') +% ylabel('y') +% zlabel('z') +% hold off +% +% figure(5) +% gcf = figure(5); +% set(gcf,'name', sprintf("tag16_05_%05d.png", infernce)); +% for i = 1:size(tag.sim.noisy.points.x, 2) +% scatter3(tag.sim.noisy.points.x(i), tag.sim.noisy.points.y(i), tag.sim.noisy.points.z(i), 'or', 'MarkerFaceColor', 'r', 'MarkerFaceAlpha', tag.sim.noisy.points.plotting.normalized_intensity(i)) +% hold on +% end +% scatter3(tag.sim.noise_free.points.x, tag.sim.noise_free.points.y, tag.sim.noise_free.points.z, '.b') +% scatter3(tag.scatter3.x, tag.scatter3.y, tag.scatter3.z, 'ok') +% plot3(reshape(tag.plot3.x,2,[]),reshape(tag.plot3.y,2,[]), reshape(tag.plot3.z,2,[]), 'k') +% surf(tag.sim.noisy.points.normalized_distribution, plotting.plot_x, plotting.plot_y, 'AlphaData', 0.1,'FaceAlpha', 0.5) +% axis equal +% xlabel('x') +% ylabel('y') +% zlabel('z') +% hold off +% disp('Done plotting') +% drawnow +% end +% infernce_old = infernce; +% end +% %% Compare similarity +% % load examgrades +% % test1 = grades(:,1); +% % x = (test1-75)/10; +% % h = kstest(x) +% % cdfplot(x) +% % hold on +% % x_values = linspace(min(x),max(x)); +% % plot(x_values,normcdf(x_values,0,1),'r-') +% % legend('Empirical CDF','Standard Normal CDF','Location','best') +% %% +% disp("Comparing distribution ...") +% fprintf(" --- Target: %s \n --- Inference: %s \n", ... +% sprintf("tag16_05_%05d.png", target), sprintf("tag16_05_%05d.png", infernce)) +% intensity_matrix = intensityToMatrix(tag.sim.noisy.points.x, ... +% tag.sim.noisy.points.y, ... +% tag.sim.noisy.points.z, ... +% tag.sim.noisy.points.intensity); +% +% intensity_matrix2 = intensityToMatrix(plotting.plot_x, plotting.plot_y, ... +% zeros(1, size(tag.sim.noisy.points.z, 2)), ... +% tag.img.normalized_distribution); +% score = computeDistributionCost(intensity_matrix, intensity_matrix2); +% score_table(target+1, infernce+1) = {score}; +% if plotting.pause +% % tag.img.normalized_distribution +% disp('Pausing ...') +% pause +% end +% end +% end +% %% +% disp("--- Results") +% score_table +% [~,max_tag] = max(table2array(score_table, [], 2), [], 1); +% max_tag = max_tag -1 \ No newline at end of file diff --git a/matlab/function_dictionary/test_gradient.m b/matlab/function_dictionary/test_gradient.m new file mode 100644 index 0000000..7a943cd --- /dev/null +++ b/matlab/function_dictionary/test_gradient.m @@ -0,0 +1,76 @@ +clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +loadLibraries(2); + + +lie = 1; + +if lie == 1 + r = sym('r%d%d',[1 3]); + R = Exp_SO3(r); + % rpy = sym('rpy%d%d',[1 3]); + % R = rotx(rpy(1)) * roty(rpy(2)) * rotz(rpy(3)); + T = sym('t%d%d', [3 1]); + H = [R T; 0 0 0 1]; + + % 3D pionts + num_points = 2; + X = sym('X%d', [1, num_points]); + Y = sym('Y%d', [1, num_points]); + Z = sym('Z%d', [1, num_points]); + points = [X;Y;Z;ones(1, num_points)]; + points_trans = simplify(H * points); + + % + H_vec = [r, transpose(T)]; + + + d_px = simplify(jacobian(points_trans(1), H_vec)); + d_py = simplify(jacobian(points_trans(2), H_vec)); + d_pz = simplify(jacobian(points_trans(3), H_vec)); + + disp("saving d_px") + matlabFunction(d_px,'File','d_px_lie'); + + disp("saving d_py") + matlabFunction(d_py,'File','d_py_lie'); + + disp("saving d_pz") + matlabFunction(d_pz,'File','d_pz_lie'); +elseif lie == 0 + rpy = sym('rpy%d%d',[1 3]); + R = rotx_sym(rpy(1)) * roty_sym(rpy(2)) * rotz_sym(rpy(3)); + T = sym('t%d%d', [3 1]); + H = [R T; 0 0 0 1]; + + % 3D pionts + num_points = 1; + X = sym('X%d', [1, num_points]); + Y = sym('Y%d', [1, num_points]); + Z = sym('Z%d', [1, num_points]); + points = [X;Y;Z;ones(1, num_points)]; +% test = H * points; + points_trans = simplify(H * points); + + H_vec = [rpy, transpose(T)]; + + d_px_euler = simplify(jacobian(points_trans(1, :), H_vec)); + d_py_euler = simplify(jacobian(points_trans(2, :), H_vec)); + d_pz_euler = simplify(jacobian(points_trans(3, :), H_vec)); + +% disp("saving d_px") +% matlabFunction(d_px_euler,'File','d_px_euler'); +% +% disp("saving d_py") +% matlabFunction(d_py_euler,'File','d_py_euler'); +% +% disp("saving d_pz") +% matlabFunction(d_pz_euler,'File','d_pz_euler'); +end + + +disp("Done") + + + + diff --git a/matlab/function_dictionary/transformToTemplate.m b/matlab/function_dictionary/transformToTemplate.m new file mode 100644 index 0000000..0c899bd --- /dev/null +++ b/matlab/function_dictionary/transformToTemplate.m @@ -0,0 +1,37 @@ +function out_t = transformToTemplate(opt, opts, X) + + [~, centroid, U] = computePlaneReturnR(X(1:3,:)); + if abs(det(U) -1) > 1e-5 + rotm_init = U(:, [3 2 1])'; + else + rotm_init = U(:, [3 1 2])'; + end + + out_t.target_size = opts.target_size; + opt.UseCentroid = 0; + opt.rpy_init = rad2deg(rotm2eul(rotm_init, "XYZ")); + % opt.rpy_init = rad2deg(rotm2eul(rotm_init)); + opt.T_init = -rotm_init*centroid(1:3); + opt.simulation_data = 0; % don't change, used in findSuitableVertices_v2.m + opt.method = "Constraint Customize Lie Group"; + + % clean up data + [~, ~, clean_up_indices, ~] = removeLiDARTargetOutliers(X, out_t.target_size, opt); + out_t.X_clean = X(:, clean_up_indices); + + % optimize pose and vertices + % opt.T_init = -rotm_init*centroid(1:3) + [-0.1 -0.5 -0.5]'; + + opt = optimizeCost(opt, out_t.X_clean, out_t.target_size, opts.box_width); + out_t.cost = opt.opt_total_cost; + out_t.computation_time = opt.computation_time; + [~, X_h] = checkHomogeneousCoord(out_t.X_clean(1:3, :), 1); + pionts_ideal_frame = opt.H_opt * X_h; % + out_t.pionts_ideal_frame = [pionts_ideal_frame(1:3, :); out_t.X_clean(4, :)]; + out_t.projected_vertices = opt.H_opt\converToHomogeneousCoord(opt.ideal_frame); + + + out_t.H_init = [rotm_init, opt.T_init; 0 0 0 1]; + out_t.pionts_initial_guess = out_t.H_init * X_h; % + out_t.pionts_initial_guess = [out_t.pionts_initial_guess(1:3, :); out_t.X_clean(4, :)]; +end \ No newline at end of file diff --git a/matlab/genTables.m b/matlab/genTables.m new file mode 100644 index 0000000..fa7d739 --- /dev/null +++ b/matlab/genTables.m @@ -0,0 +1,154 @@ +clear, clc +% addpath(genpath("E:/2020summer_research/matlab/matlab_utils-master")); +% addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); +opts.data_path = "./paper_data/"; + + + +analyze_package = 1; % analyze each step of the pipeline +% event = 4; % which date +dataset = 2; % 1: front 2: ccw +tag_size = 1.22; +TextData = getTextData(opts); + + + +%% Compare with ground truth +gt_ID = 0; +gt_rot_num = 3; +num_estimates = 7; +results(num_estimates) = struct('name', [], 'distance', [], 'num_scans', [], ... + 'ID_ratio', [], 'translation', [], 'geodesic', []); +for i = (1 + num_estimates * (dataset - 1)) : ... + (num_estimates + num_estimates * (dataset-1)) + if (isempty(TextData(i).pose_raw_data)) + continue; + end + + + results(i).name = TextData(i).name; + results(i).distance = norm(TextData(i).translation); + results(i).num_scans = size(TextData(i).pose_raw_data, 1); + results(i).ID = length(find(abs((TextData(i).id - gt_ID)))); + results(i).rot_num = ... + length(find(abs((TextData(i).rot_num - gt_rot_num)))); + + results(i).ID_ratio = results(i).ID / results(i).num_scans; + results(i).rot_num_ratio = ... + results(i).rot_num / results(i).num_scans; + + i; + % translation is in mm + results(i).translation = ... + (TextData(i).translation - TextData(i).est_translation) * 1000; + results(i).translation = ... + norm((TextData(i).translation - TextData(i).est_translation) * 1000); + + results(i).rpy = ... + TextData(i).rpy - TextData(i).est_rpy + TextData(i).change_coordinate; + results(i).geodesic = rad2deg(norm(Log_SO3(eul2rotm(deg2rad(results(i).rpy), "XYZ")))); + results(i).dH = TextData(i).L_H_LT / TextData(i).est_L_H_LT; +end + +disp("===============================================================") +disp("=========== Results of Decoding and Pose Estimation ===========") +disp("===============================================================") +results(all(cell2mat(arrayfun( @(x) structfun( @isempty, x), ... + results, 'UniformOutput', false)), 1)) = []; +struct2table(results) + +disp("===============================================================") +disp("=========== Summary of Decoding and Pose Estimation ===========") +disp("===============================================================") +disp("-- mean:") +fprintf("---- Number of scans: %.3f\n", mean([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", mean([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", mean([results.geodesic])) +fprintf("---- ID ratio [%]: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) + +disp("-- median:") +fprintf("---- Number of scans: %.3f\n", median([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", median([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", median([results.geodesic])) + +disp("-- std:") +fprintf("---- Number of scans: %.3f\n", std([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", std([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", std([results.geodesic])) + + + + +%% Package general analysis +if analyze_package + %% summary + disp("===============================================================") + disp("============= Summary Results of General Analysis =============") + disp("===============================================================") + + summary_t_hz = summarizeGeneralAnalysis(TextData, "hz"); + summary_t_mean = summarizeGeneralAnalysis(TextData, "mean"); + disp("-----------------------------------------------------------") + fprintf("Average over all dadtasets with %i scans \n", ... + summary_t_hz.total_scans) + disp("-----------------------------------------------------------") + + disp("--- Computation time [Hz]-----") + struct2table(summary_t_hz.computation_hz) + + disp("--- Computation time of each step [Hz]-----") + note = "Note: Due to calling the timing function hundreds of times " + ... + "to time each function in the pipeline, " + ... + "the total computation time is slower than the above. \n"; + fprintf(note) + struct2table(summary_t_hz.timing_hz) + + disp("--- Computation time of each step [ms]-----") + struct2table(summary_t_mean.timing_mean) + + disp("--- Cluster removal in each step -----") + struct2table(summary_t_hz.clusters) + + disp("----- Speed of double sum -----") + struct2table(summary_t_mean.decoding_mean) + +end + + +%% False positives +for i = 1:3 + data_num = i; + + + switch data_num + case 1 + dataset = "cartographer/horizontal_lidar"; + case 2 + dataset = "cartographer/vertical_lidar"; + case 3 + dataset = "H3D"; + end + path_folder = opts.data_path + "public_datasets/" + dataset + "/stats.txt"; + delimiterIn = ','; + headerlinesIn = 1; + + disp("===============================================================") + fprintf("====== False Positives for %s dataset ======\n", ... + dataset) + disp("===============================================================") + data.pose_raw_data = dlmread(path_folder, ',', 1, 0); + data.num_scan = size(data.pose_raw_data, 1); + false_positives_index = find(data.pose_raw_data(:, size(data.pose_raw_data, 2))); + data.pose_raw_data(false_positives_index, :); + data.false_positives = length(false_positives_index); + data.false_positives_ratio = length(false_positives_index)/data.num_scan * 100 +end + + +%% Indoor +disp("Compuration time in a cluttered laboratory") +indoor_path = opts.data_path + "indoor/"; +indoor = analyzeLiDARTagPackage([], indoor_path); +disp("--- Computation time [Hz]-----") +struct2table(indoor.computation_hz) \ No newline at end of file diff --git a/matlab/getSingleTextData.m b/matlab/getSingleTextData.m new file mode 100644 index 0000000..e80dffe --- /dev/null +++ b/matlab/getSingleTextData.m @@ -0,0 +1,46 @@ +function SingleTextData = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,i) + SingleTextData.change_coordinate = change_coordinate; + SingleTextData.tag_size = tag_size; + lidar_path = root_path + "gt_lidar/"; + lt_estimate_path = root_path + "lidartag_estimates/"; + lidar_files = dir(lidar_path + prefix + "*.txt"); + lidar_file = lidar_files(i).name; + SingleTextData.name = ... + lidar_file(... + 1:strfind(lidar_file, '.') - 1); + lidar_data = ... + mean(dlmread(lidar_path + lidar_files(i).name, ',', 1, 0)); + SingleTextData.lidar_corners = ... + [lidar_data(2:4)', lidar_data(5:7)', ... + lidar_data(8:10)', lidar_data(11:13)']; + out_t = computePoseFromLiDARToMocapMarkers(... + SingleTextData.lidar_corners, mocap_corners, tag_size, corner_order); + + for fn = fieldnames(out_t)' + SingleTextData.(fn{1}) = out_t.(fn{1}); + end + + + name = prefix + num2str(i); + lt_current_path = lt_estimate_path + name + "/"; + pose_file = dir(lt_current_path + "*1.2*pose.txt"); + + % pose data + pose_raw_data = dlmread(lt_current_path + pose_file.name, ',', 1, 0); + SingleTextData.pose_raw_data = pose_raw_data; + SingleTextData.iter = pose_raw_data(:, 1); + SingleTextData.id = pose_raw_data(:, 2); + SingleTextData.rot_num = pose_raw_data(:, 3); + [SingleTextData.rotm, SingleTextData.est_translation] = ... + computeMeanOfTranslationNRotation(... + pose_raw_data(:, 7:end), ... + pose_raw_data(:, 4:6)); + SingleTextData.est_L_H_LT = eye(4); + SingleTextData.est_L_H_LT(1:3, 1:3) = SingleTextData.rotm; + SingleTextData.est_L_H_LT(1:3, 4) = SingleTextData.est_translation; + SingleTextData.est_rpy = ... + rad2deg(rotm2eul(SingleTextData.est_L_H_LT(1:3, 1:3), 'XYZ')); + + % General Analysis + SingleTextData = analyzeLiDARTagPackage(SingleTextData, lt_current_path); +end \ No newline at end of file diff --git a/matlab/getTextData.m b/matlab/getTextData.m new file mode 100644 index 0000000..dae990a --- /dev/null +++ b/matlab/getTextData.m @@ -0,0 +1,203 @@ +function TextData = getTextData(opts) + root_path = opts.data_path; + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct11-2020/front1 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct11-2020/"; + prefix = "front"; + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + + TextData(1) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,1); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct11-2020/front2 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct11-2020/"; + prefix = "front"; + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(2) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,2); + + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct11-2020/front3 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct11-2020/"; + prefix = "front"; + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(3) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,3); + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct11-2020/front4 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct11-2020/"; + prefix = "front"; + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(4) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,4); + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct11-2020/front5 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct11-2020/"; + prefix = "front"; + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(5) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,5); + + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct7-2020/front6 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct07-2020/"; + prefix = "front"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [1, 2, 3, 4]; + tag_size = 1.22; + TextData(6) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,6); + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct7-2020/front7 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct07-2020/"; + prefix = "front"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [1, 2, 3, 4]; + tag_size = 1.22; + TextData(7) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,7); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct13-2020/ccw1-1 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct13-2020/"; + prefix = "ccw1-"; + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(8) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,1); + + + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct13-2020/ccw1-2 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct13-2020/"; + prefix = "ccw1-"; + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(9) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,2); + + + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct13-2020/ccw1-3 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct13-2020/"; + prefix = "ccw1-"; + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(10) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,3); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct13-2020/ccw1-4 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct13-2020/"; + prefix = "ccw1-"; + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(11) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,4); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct13-2020/ccw1-5 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct13-2020/"; + prefix = "ccw1-"; + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [2, 3, 4, 1]; + tag_size = 1.22; + TextData(12) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,5); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct07-2020/ccw1-6 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct07-2020/"; + prefix = "ccw1-"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [1, 2, 3, 4]; + tag_size = 1.22; + TextData(13) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,6); + + %%%%%%%%%%%%%%%%%%%%%%%%%%%% + % Oct07-2020/ccw1-7 + %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% event_name = "Oct07-2020/"; + prefix = "ccw1-"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + change_coordinate = [0, 0, -180]; + corner_order = [1, 2, 3, 4]; + tag_size = 1.22; + TextData(14) = getSingleTextData(root_path, prefix, tag_size, change_coordinate, corner_order, mocap_corners,7); +end + diff --git a/matlab/main.m b/matlab/main.m new file mode 100644 index 0000000..a4a6c9e --- /dev/null +++ b/matlab/main.m @@ -0,0 +1,371 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + +analyze_package = 1; % analyze each step of the pipeline +event = 2; % which date +dataset = 2; % 1: front 2: ccw +tag_size = 1.22; + + + +%% Which date and which datasets +switch event + case 1 + event_name = "Oct01-2020/"; + dataset = dataset; + % dataset: 1 + case 2 + event_name = "Oct07-2020/"; + dataset = dataset; + % dataset: 1 or 2 + case 3 + event_name = "Oct11-2020/"; + % dataset: 3 or 4 + dataset = 2 + dataset; + case 4 + event_name = "Oct13-2020/"; + % dataset: 5 or 6 + dataset = 4 + dataset; +end + + +%% Load mocap corners and assign correspondances +switch dataset + case 1 + prefix = "ccw1-"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + % top, right, bottom, left + change_coordinate = [0, 0, 180]; + corner_order = [1, 2, 3, 4]; + + case 2 + prefix = "ccw1-"; + mocap_corners = [-1231.2, -678.92, -1486.8, -2039.1; + 7823, 7674.8, 8384.2, 8532.5; + -1.1026, -1043, -1562.1, -520.13] ./ 1000; + change_coordinate = [0, 0, -180]; + % top, right, bottom, left + corner_order = [1, 2, 3, 4]; + case 3 + prefix = "front"; + % right, bottom, left, top + mocap_corners = [-463.5, -1.397e3, -2.139e3, -1.21e3; + 1.04e4, 1.05e4, 1.023e4, 1.011e4; + -893.48, -1.629e3, -740.55, -5.4412] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; + case 4 + prefix = "ccw1-"; + corner_order = [2, 3, 4, 1]; + mocap_corners = [-444.32, -1.21e3, -1.97e3, -1.2e3; + 1.01e4, 1.07e4, 1.078e4, 1.021e4; + -920.093, -1.62e3, -708.135, -1.0498] ./ 1000; + case 5 + prefix = "front"; + % right, bottom, left, top + mocap_corners = [-1207.00473282087,-162.398350868965,407.243820707562,-645.857194240357 + 8849.07949318208,8649.68879356377,8788.08379357059,8982.60086074787 + -664.681198185466,-134.780774365747,-1182.68393961901,-1712.23067661678] ./ 1000; + change_coordinate = [0, 0, 180]; + corner_order = [2, 3, 4, 1]; +% corner_order = [1,2,3,4]; + case 6 + prefix = "ccw1-"; + corner_order = [2, 3, 4, 1]; + % right, bottom, left, top + mocap_corners = [ + -1048.59669393742,-340.305804296641,625.935265764107,-88.8040158428149 + 8880.42788298431,8660.87423516959,8709.80064463733,8930.80568283424 + -1033.10454793262,-101.79535034276,-815.690194430646,-1745.58145924785] ./ 1000; + change_coordinate = [0, 0, -180]; +end + + +%% Path +root_path = "./paper_data_pre/"; +lidar_path = root_path + "gt_lidar/" + event_name; +lt_estimate_path = root_path + "lidartag_estimates/" + event_name; +% camera_path = root_path + "gt_camera/" + event_name; +lt_estimate_folers = dir(lt_estimate_path + prefix + "*"); +num_estimates = size(lt_estimate_folers, 1); + + + +%% Load data from txt files (ground truth data) +lidar_files = dir(lidar_path + prefix + "*.txt"); +num_lidar_files = length(lidar_files); +% camera_files = dir(camera_path + prefix + "*.txt"); +% num_camera_files = length(camera_files); +% num_data = min(num_lidar_files, num_camera_files); +num_data = num_lidar_files; + +ground_truth(num_data) = struct(); +for i = 1:num_data + % find idar file in camera files + ground_truth(i).lidar_file = lidar_files(i).name; +% index = find(strcmp({camera_files.name}, ... +% ground_truth(i).lidar_file)==1); + + ground_truth(i).name = ... + ground_truth(i).lidar_file(... + 1:strfind(ground_truth(i).lidar_file, '.') - 1); + + % load lidar data + lidar_data = ... + mean(dlmread(lidar_path + lidar_files(i).name, ',', 1, 0)); + ground_truth(i).lidar_corners = ... + [lidar_data(2:4)', lidar_data(5:7)', ... + lidar_data(8:10)', lidar_data(11:13)']; + +% % load camera data +% ground_truth(i).camera_file = camera_files(index).name; +% camera_data = ... +% mean(dlmread(camera_path + ... +% ground_truth(i).camera_file, ',', 1, 0)); +% ground_truth(i).camera_corners = ... +% [camera_data(2:4)', camera_data(5:7)', ... +% camera_data(8:10)', camera_data(11:13)']; +% +% % assert if names are not the same +% assert(... +% strcmp(ground_truth(i).camera_file, ... +% ground_truth(i).lidar_file), "files mismatch") + + + out_t = computePoseFromLiDARToMocapMarkers(... + ground_truth(i).lidar_corners, mocap_corners, tag_size, corner_order); + + for fn = fieldnames(out_t)' + ground_truth(i).(fn{1}) = out_t.(fn{1}); + end +end + + +%% Load estimated LiDARTag pose/ID information +lidartag(length(num_estimates)) = struct('name', [], 'pose_file', [],... + 'pose_raw_data', [], 'iter', [], ... + 'id', [], 'rot_num', [], 'rotm', [], 'translation', [], ... + 'L_H_LT', [], 'rpy', [], ... + 'num_data', [], 'computation_hz', [], 'computation_mean', [],... + 'decoding_hz', [], 'decoding_mean', [], ... + 'timing_hz', [], 'timing_mean', [], 'clusters', []); +for i = 1:num_estimates + lidartag(i).name = prefix + num2str(i); + lt_current_path = lt_estimate_path + lidartag(i).name + "/"; + lidartag(i).pose_file = dir(lt_current_path + "*1.2*pose.txt"); + + if isempty(lidartag(i).pose_file) + continue + end + + % pose data + lidartag(i).pose_raw_data = dlmread(... + lt_current_path + lidartag(i).pose_file.name, ',', 1, 0); + + lidartag(i).iter = lidartag(i).pose_raw_data(:, 1); + lidartag(i).id = lidartag(i).pose_raw_data(:, 2); + lidartag(i).rot_num = lidartag(i).pose_raw_data(:, 3); + [lidartag(i).rotm, lidartag(i).translation] = ... + computeMeanOfTranslationNRotation(... + lidartag(i).pose_raw_data(:, 7:end), ... + lidartag(i).pose_raw_data(:, 4:6)); + lidartag(i).L_H_LT = eye(4); + lidartag(i).L_H_LT(1:3, 1:3) = lidartag(i).rotm; + lidartag(i).L_H_LT(1:3, 4) = lidartag(i).translation; + lidartag(i).rpy = ... + rad2deg(rotm2eul(lidartag(i).L_H_LT(1:3, 1:3), 'XYZ')); + + if analyze_package + lidartag(i) = analyzeLiDARTagPackage(lidartag(i), lt_current_path); + else + lidartag(i).num_data = size(lidartag(i).pose_raw_data, 1); + end +end + + +%% Compare with ground truth +gt_ID = 0; +gt_rot_num = 3; +results(num_data) = struct('name', [], 'distance', [], 'num_scans', [], ... + 'ID_ratio', [], 'translation', [], 'geodesic', []); +for i = 1:num_estimates + if (isempty(lidartag(i).pose_raw_data)) + continue; + end + + index = find(strcmp({ground_truth.name}, lidartag(i).name)==1); + if isempty(index) + continue; + end + + results(i).name = lidartag(i).name; + results(i).distance = norm(ground_truth(index).translation); + results(i).num_scans = lidartag(i).num_data; + results(i).ID = length(find(abs((lidartag(i).id - gt_ID)))); + results(i).rot_num = ... + length(find(abs((lidartag(i).rot_num - gt_rot_num)))); + + results(i).ID_ratio = results(i).ID / lidartag(i).num_data; + results(i).rot_num_ratio = ... + results(i).rot_num / lidartag(i).num_data; + + i; + % translation is in mm + results(i).translation = ... + (ground_truth(index).translation - lidartag(i).translation) * 1000; + results(i).translation = ... + norm((ground_truth(index).translation - lidartag(i).translation) * 1000); + + results(i).rpy = ... + ground_truth(index).rpy - lidartag(i).rpy + change_coordinate; + results(i).geodesic = rad2deg(norm(Log_SO3(eul2rotm(deg2rad(results(i).rpy), "XYZ")))); + results(i).dH = ground_truth(index).L_H_LT / lidartag(i).L_H_LT; +end + +disp("===============================================================") +disp("=========== Results of Decoding and Pose Estimation ===========") +disp("===============================================================") +results(all(cell2mat(arrayfun( @(x) structfun( @isempty, x), ... + results, 'UniformOutput', false)), 1)) = []; +struct2table(results) + + +%% Package general analysis +if analyze_package + disp("===============================================================") + disp("================= Results of General Analysis =================") + disp("===============================================================") + for i = 1:num_estimates + dataset_num = i; + if isempty(lidartag(dataset_num).num_data) + warning("No results for %s", lidartag(dataset_num).name) + else + disp("-------------------------------------------------------") + fprintf("Each of below average over %i scans ", ... + lidartag(dataset_num).num_data) + fprintf("from %s dataset: \n", lidartag(dataset_num).name) + disp("-------------------------------------------------------") + struct2table(lidartag(dataset_num).computation_hz) + + if isempty(lidartag(dataset_num).timing_hz) + warning("No timing_hz for %s dataset", ... + lidartag(dataset_num).name) + else + struct2table(lidartag(dataset_num).timing_hz) + end + + struct2table(lidartag(dataset_num).clusters) + + if isempty(lidartag(dataset_num).decoding_hz) + warning("No decoding_hz for %s dataset", ... + lidartag(dataset_num).name) + else + struct2table(lidartag(dataset_num).decoding_hz) + end + end + end + + %% summary + disp("===============================================================") + disp("============= Summary Results of General Analysis =============") + disp("===============================================================") + + summary_t = summarizeGeneralAnalysis(lidartag, "hz"); + disp("-----------------------------------------------------------") + fprintf("Average Hz over all dadtasets with %i scans \n", ... + summary_t.total_scans) + disp("-----------------------------------------------------------") + + t1 = struct2table(summary_t.computation_hz) + t2 = struct2table(summary_t.timing_hz) + t3 = struct2table(summary_t.clusters) + + if isfield(summary_t, 'decoding_hz') + t4 = struct2table(summary_t.decoding_hz) + end + + + disp("-----------------------------------------------------------") + fprintf("Average ms over all dadtasets with %i scans \n", ... + summary_t.total_scans) + disp("-----------------------------------------------------------") + summary_t = summarizeGeneralAnalysis(lidartag, "mean"); + t1 = struct2table(summary_t.computation_mean) + t2 = struct2table(summary_t.timing_mean) + t3 = struct2table(summary_t.clusters) + if isfield(summary_t, 'decoding_mean') + t4 = struct2table(summary_t.decoding_mean) + end +end +% t5 = array2table(table2array(struct2table(summary_t.computation_hz)).'); +% t5.Properties.RowNames = t1.Properties.VariableNames; +% t5.Properties.VariableNames = "Hz"; +% t5 + + + + + +%% Plottings +% X = ground_truth(1).lidar_corners'; % n x 3 +% Y = mocap_corners'; % n x 3 +% [~, mocap_at_lidar, ~] = procrustes(X, Y, 'scaling', 0, 'reflection', 0); +% +% template = [0, 0, 0, 0; +% tag_size/2, -tag_size/2, -tag_size/2 ,tag_size/2; +% tag_size/2, tag_size/2, -tag_size/2, -tag_size/2]'; +% [d, ~, transform] = ... +% procrustes(mocap_at_lidar, template, 'scaling', 0, 'reflection', 0); +% H_ML = eye(4); +% H_ML(1:3, 1:3) = transform.T'; +% H_ML(1:3, 4) = transform.c(1, :)'; +% mocap_lidar = H_ML * convertToHomogeneousCoord(template'); +% +% +% +% [axes_h, fig_h] = createFigHandleWithNumber(2, 1, "pose", 1, 1); +% cur_axes = axes_h(1); +% h1 = scatter3(cur_axes, X(:, 1), X(:, 2), X(:, 3), 'ko'); +% h2 = scatter3(cur_axes, Y(:, 1), Y(:, 2), Y(:, 3), 'b.'); +% h3 = scatter3(cur_axes, ... +% mocap_at_lidar(:, 1), ... +% mocap_at_lidar(:, 2), ... +% mocap_at_lidar(:, 3), 'rx'); +% legend([h1, h2, h3], ... +% ["L_lidar_corners", "M_mocap_corners", "L_mocap_corners"]) +% plotColoredOriginAxisWithText(cur_axes, "LiDAR", eye(4), 0.5) +% showCurrentPlot(cur_axes, "Mocap to LiDAR", [-50, 30]) +% +% +% cur_axes = axes_h(2); +% scatter3(cur_axes, ... +% template(:, 1), template(:, 2), template(:, 3), ... +% 'fill', 'ko') +% scatter3(cur_axes, X(:, 1), X(:, 2), X(:, 3), 'bo') +% scatter3(cur_axes, ... +% mocap_lidar(1, :), mocap_lidar(2, :), mocap_lidar(3, :), 'r*') +% % scatter3(... +% cur_axes, mocap_lidar(:, 1), mocap_lidar(:, 2), mocap_lidar(:, 3), 'r*') +% plotColoredOriginAxisWithText(cur_axes, "LiDAR", eye(4), 0.5) +% showCurrentPlot(cur_axes, "LiDAR", [-70, 10]) + + + + + + + + + + + + + + + + + diff --git a/matlab/main_backup.m b/matlab/main_backup.m new file mode 100644 index 0000000..be97b1a --- /dev/null +++ b/matlab/main_backup.m @@ -0,0 +1,312 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +% Files +mocap_path = "./new_preprocess/"; +datasets = 1; + + + +%% Datasets +if datasets == 1 + mocap_name = "CCW1"; + mocap_files = load(mocap_path + mocap_name + ".mat"); + + distance(1,:) = [318,1834]; + distance(2,:) = [2792,5156]; + distance(3,:) = [5779,6880]; + distance(4,:) = [7422,8925]; + distance(5,:) = [9625,11170]; + distance(6,:) = [11850,13270]; + estimation_indices = [6]; + +elseif datasets == 2 + mocap_name = "straight_front1"; + mocap_files = load(mocap_path + mocap_name + ".mat"); + + + distance(1,:) = [44, 2188]; + distance(2,:) = [2900, 3252]; + distance(3,:) = [4053, 4681]; + distance(4,:) = [5026, 5498]; + distance(5,:) = [6935, 8542]; + distance(6,:) = [8977, 9519]; + estimation_indices = 2:5; +end + +lt_estimate_path = "./paper_data/" + lower(mocap_name) + "-"; + +% apriltag estimatation path +at_estimate_path = mocap_path + ... + "predictions/apriltag_prediction/" + ... + lower(mocap_name) + "-"; + +%% Frame assignment +for k = 1:mocap_files.(mocap_name).RigidBodies.Bodies + if strcmp(mocap_files.(mocap_name).RigidBodies.Name(k),'lidar') + lidar_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + lidar_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + tag_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + end +end + + +%% Remove invalid data points +n = 1; +invalid_num = 0; +total_frames = mocap_files.(mocap_name).Frames; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || ... + any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || ... + any(isnan(tag_rot_raw(:,:,m))); + + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end + +valid_frames = n - 1; +lidart = 1:valid_frames; +y = squeeze(lidar_pos(1, 1,:)); +figure(1); +scatter(lidart,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 2,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 3,:)); +figure(3); +scatter(p,q,'filled'); + + + +%% Frame conversion +R_L1L2 = rotx(180) * roty(0) * rotz(-92); +R_T1T2 = rotx(200) * roty(-7)* rotz(-85); +O_L2_in_L1 = [0.12 0.0 0.12]'; +O_T2_in_T1 = [0, 0, 0]'; +H_L1L2 = constructHByRotationTranslation(R_L1L2, -R_L1L2 * O_L2_in_L1); +H_T1T2 = constructHByRotationTranslation(R_T1T2, -R_T1T2 * O_T2_in_T1); + + + +%% Mocap data +num_mocap_data = size(distance, 1); +mocap_results(num_mocap_data) = struct(); +for i = 1:num_mocap_data + % LiDAR 1 + L1_trans_mean = ... + mean(lidar_pos(1, :, distance(i,1):distance(i,2)), 3) ./ 1000; + L1_rot_mean = mean(lidar_rot(1, :, distance(i,1):distance(i,2)), 3); + + % Target 1 + T1_trans_mean = ... + mean(tag_pos(1, :, distance(i,1):distance(i,2)), 3) ./ 1000; + T1_rot_mean = mean(tag_rot(1, :, distance(i,1):distance(i,2)), 3); + + % Convert rotm from 1x9 to 3x3 + L1_rotm = reshape(L1_rot_mean, 3, 3); + T1_rotm = reshape(T1_rot_mean, 3, 3); + + % Construct H + H_W1T1 = constructHByRotationTranslation(... + T1_rotm', -T1_rotm' * T1_trans_mean'); + H_W1L1 = constructHByRotationTranslation(... + L1_rotm', -L1_rotm' * L1_trans_mean'); + + %%%%%%%%%%%%%% + mocap_results(i).M_H_L2T2 = (H_T1T2 * H_W1T1) / (H_L1L2 * H_W1L1); + mocap_results(i).M_R_L2T2 = mocap_results(i).M_H_L2T2(1:3, 1:3); + mocap_results(i).M_O_T2_in_L2 = ... + -mocap_results(i).M_R_L2T2 \ mocap_results(i).M_H_L2T2(1:3, 4); + mocap_results(i).M_rpy = ... + rad2deg(rotm2eul(mocap_results(i).M_R_L2T2, 'XYZ')); + mocap_results(i).M_trans = mocap_results(i).M_O_T2_in_L2; +end + +%% Estimated data +lidartag_results(num_mocap_data) = struct(); +apriltag_results(num_mocap_data) = struct(); +for i = estimation_indices + lt_current_path = lt_estimate_path + num2str(i) + "/"; + lt_estimate_file = dir(lt_current_path + "*1.2*.txt"); + lidart = dlmread(lt_current_path + lt_estimate_file.name, ',', 1, 0); + + L_trans_L2T2_raw = mean(lidart(:, 4:6), 1); + L_rotm_L2T2_raw = reshape(mean(lidart(1, 7:end), 1), [], 3)'; + L_rpy_L2T2_raw = rad2deg(rotm2eul(L_rotm_L2T2_raw(1:3,1:3), 'XYZ')); + + L_H_L2T2_raw = constructHByRotationTranslation(L_rotm_L2T2_raw, L_trans_L2T2_raw); + L_H_L2T2 = inv(L_H_L2T2_raw); + + %%%%%%%%%%%%%% + lidartag_results(i).L_H_L2T2 = L_H_L2T2; + lidartag_results(i).L_R_L2T2 = L_H_L2T2(1:3, 1:3); + lidartag_results(i).L_O_T2_in_L2 = ... + -lidartag_results(i).L_R_L2T2 \ L_H_L2T2(1:3, 4); + lidartag_results(i).L_rpy = rad2deg(rotm2eul(lidartag_results(i).L_R_L2T2, 'XYZ')); + lidartag_results(i).L_trans = lidartag_results(i).L_O_T2_in_L2; + + +% at_current_path = at_estimate_path + num2str(i) + "/"; +% at_estimate_file = dir(at_current_path + "*april.txt"); +% apriltag = dlmread(at_current_path + at_estimate_file.name, ',', 1, 0); +end + + + +%% Results +distance = [mocap_results(estimation_indices).M_trans]; +restuls.distance = distance(1, :); +restuls.trans = ... + ([mocap_results(estimation_indices).M_trans] - ... + [lidartag_results(estimation_indices).L_trans])'; +restuls.rpy = ... + [mocap_results(estimation_indices).M_rpy] - ... + [lidartag_results(estimation_indices).L_rpy] + [90-45, 0 180]; +struct2table(restuls, 'AsArray', 1) + +%% Tables +% T = table(Distance_meter, ... +% d_x_meter, d_y_meter, d_z_meter, ... +% d_r_degree,d_p_degree,d_h_degree) + + +%% Plottings +% figure(1); +% plot(M_trans_L2T2(estimation_indices, 1), d_x_meter); +% +% figure(2); +% plot(M_trans_L2T2(estimation_indices, 1), d_y_meter); +% +% figure(3); +% plot(M_trans_L2T2(estimation_indices, 1), d_z_meter); +% +% figure(4); +% plot(M_trans_L2T2(estimation_indices, 1), d_r_degree); +% +% figure(5); +% plot(M_trans_L2T2(estimation_indices, 1), d_p_degree); +% +% figure(6); +% plot(M_trans_L2T2(estimation_indices, 1), d_h_degree); + + +%% +% num_data = 3; +% +% % LiDAR 1 +% L1_trans_mean = mean(lidar_pos(1,:,distance(num_data,1):distance(num_data,2)),3)./1000; +% L1_rot_mean = mean(lidar_rot(1,:,distance(num_data,1):distance(num_data,2)),3); +% +% % Target 1 +% T1_trans_mean = mean(tag_pos(1,:,distance(num_data,1):distance(num_data,2)),3)./1000; +% T1_rot_mean = mean(tag_rot(1,:,distance(num_data,1):distance(num_data,2)),3); +% +% % Convert rotm from 1x9 to 3x3 +% L1_rotm = reshape(L1_rot_mean, 3, 3); +% T1_rotm = reshape(T1_rot_mean, 3, 3); +% +% % Construct H +% H_W1T1 = constructHByRotationTranslation(T1_rotm, T1_trans_mean); +% H_W1L1 = constructHByRotationTranslation(L1_rotm, L1_trans_mean); +% +% % change basis +% H_L1T1 = H_W1L1 \ H_W1T1; +% H_W3W1 = eye(4); +% H_W3W1(1:3, 1:3) = roty(180) * rotz(-90); +% +% H_W1L2 = (H_W1L1 * H_L1L2); +% H_W1T2 = (H_W1T1 * H_T1T2); +% H_L2T2 = H_W1L2 \ H_W1T2; +% +% +% +% M_rpy_L2T2(i, :) = rad2deg(rotm2eul(H_L2T2(1:3,1:3), 'XYZ')); +% M_trans_L2T2(i, :) = H_L2T2(1:3,4) ./ 1000; +% +% disp("Done") +%% Testing +% [axes_h, fig_h] = createFigHandleWithNumber(5, 100,"frames", 1, 1); +% +% % Frame +% W1 = eye(4); % Frame of LiDAR Device +% +% +% W2 = eye(4); +% W2(1:3, 1:3) = rotz(-90); +% W2(1:3, 4) = 1; +% +% W3 = eye(4); +% W3(1:3, 1:3) = rotx(180) * rotz(-90); +% W3(1:3, 4) = 2; +% +% +% cur_fig = axes_h(1); +% plotColoredOriginAxisWithText(cur_fig, "W1", W1, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "W2", W2, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "W3", W3, 0.5) +% +% showCurrentPlot(cur_fig, "Frame system", [-40 30], 1) +% +% +% +% %% +% +% % Frame +% W3 = eye(4); % Frame of LiDAR Device +% W1 = eye(4); +% W1(1:3, 1:3) = rotx(180) * rotz(-90); +% % W1(1:3, 1:3) = roty(180); +% W1(1:3, 4) = 1; +% +% +% cur_fig = axes_h(1); +% plotColoredOriginAxisWithText(cur_fig, "W3", W3, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "W1", W1, 0.5) +% showCurrentPlot(cur_fig, "Frame system", [-40 30], 1) +% +% +% cur_fig = axes_h(2); +% plotColoredOriginAxisWithText(cur_fig, "Origin", eye(4), 0.5) +% plotColoredOriginAxisWithText(cur_fig, "Mocap", W1, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "LiDAR", H_W1L1 * W1, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "Tag", H_W1T1 * W1, 0.5) +% showCurrentPlot(cur_fig, "Mcap Frames", [-40 30], 1) +% +% +% +% cur_fig = axes_h(3); +% plotColoredOriginAxisWithText(cur_fig, "Origin", W1, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "LiDAR", H_W1L2 * W1, 0.5) +% plotColoredOriginAxisWithText(cur_fig, "Tag", H_W1T2 * W1, 0.5) +% showCurrentPlot(cur_fig, "LiDAR Frames", [-40 30], 1) +% +% +% +% % reloadCurrentPlot(cur_fig) +% % set(cur_fig, 'ZDir','reverse') +% % set(cur_fig, 'ZDir','normal') +% +% disp("Done") \ No newline at end of file diff --git a/matlab/new_preprocess/CCW1.m b/matlab/new_preprocess/CCW1.m new file mode 100644 index 0000000..3623494 --- /dev/null +++ b/matlab/new_preprocess/CCW1.m @@ -0,0 +1,103 @@ +clear +file = load('CCW1.mat'); +total_frames = file.CCW1.Frames; +for k = 1:file.CCW1.RigidBodies.Bodies + if strcmp(file.CCW1.RigidBodies.Name(k),'lidar') + lidar_pos_raw = file.CCW1.RigidBodies.Positions(k,:,:); + lidar_rot_raw = file.CCW1.RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = file.CCW1.RigidBodies.Positions(k,:,:); + tag_rot_raw = file.CCW1.RigidBodies.Rotations(k,:,:); + end +end + +n = 1; +invalid_num = 0; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || any(isnan(tag_rot_raw(:,:,m))); + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end +valid_frames = n - 1; +% x = 1:valid_frames; +% y = squeeze(lidar_pos(1,1,:)); +% figure(1); +% scatter(x,y,'filled'); +% p = 1:valid_frames; +% q = squeeze(lidar_pos(1,2,:)); +% figure(2); +% scatter(p,q,'filled'); +% p = 1:valid_frames; +% q = squeeze(lidar_pos(1,3,:)); +% figure(3); +% scatter(p,q,'filled'); + +mocap_to_lidar_change_of_basis = [0 1 0 0; 1 0 0 0; 0 0 -1 0; 0 0 0 1]; +new_basis = mocap_to_lidar_change_of_basis; +%CCW1 +distance(1,:) = [318,1834]; +distance(2,:) = [2792,5156]; +distance(3,:) = [5779,6880]; +distance(4,:) = [7422,8925]; +distance(5,:) = [9625,11170]; +distance(6,:) = [11850,13270]; +for i = 1:6 + lidar_pos_mean = mean(lidar_pos(1,:,distance(i,1):distance(i,2)),3); + lidar_rot_mean = mean(lidar_rot(1,:,distance(i,1):distance(i,2)),3); + tag_pos_mean = mean(tag_pos(1,:,distance(i,1):distance(i,2)),3); + tag_rot_mean = mean(tag_rot(1,:,distance(i,1):distance(i,2)),3); + lidar_rotm = reshape(lidar_rot_mean,3,3); + tag_rotm = reshape(tag_rot_mean,3,3); + world_H_tag = createSE3(tag_rotm, tag_pos_mean'); + world_H_lidar = createSE3(lidar_rotm, lidar_pos_mean'); + lidar_H_tag = world_H_lidar \ world_H_tag; + lidar_H_tag_t = new_basis * lidar_H_tag * inv(new_basis); + angles = rotm2eul(lidar_H_tag_t(1:3,1:3), 'XYZ'); + +% angles = fliplr(angles)'; +% angles = flipud(new_basis*angles)'; + tag_rotm_lidar(i,:) = angles*180/pi; + tag_pos_lidar(i,:) =lidar_H_tag_t(1:3,4)/1000; +end +tag_rotm_lidar +tag_pos_lidar +for i = 1:6 + file_name = strcat('ccw1-',int2str(i),'.txt'); + x = dlmread(file_name,',',1,0); + pose_prediction_L(i,:) = mean(x(:,4:6),1); + rot_prediction_L(i,:) = mean(x(:,7:9),1)*180/pi; +end +pose_prediction_L +rot_prediction_L +figure(1); +delta_x_meter = pose_prediction_L(:,1) - tag_pos_lidar(:,1); +plot(tag_pos_lidar(:,1),delta_x_meter); +figure(2); +delta_y_meter = pose_prediction_L(:,2) - tag_pos_lidar(:,2); +plot(tag_pos_lidar(:,1),delta_y_meter); +figure(3); +delta_z_meter = pose_prediction_L(:,3) - tag_pos_lidar(:,3); +plot(tag_pos_lidar(:,1),delta_z_meter); +figure(4); +delta_r_degree = rot_prediction_L(:,1) - tag_rotm_lidar(:,1); +plot(tag_pos_lidar(:,1),delta_r_degree); +figure(5); +delta_p_degree = rot_prediction_L(:,2) - tag_rotm_lidar(:,2); +plot(tag_pos_lidar(:,1),delta_p_degree); +figure(6); +delta_yaw_degree = rot_prediction_L(:,3) - tag_rotm_lidar(:,3); +plot(tag_pos_lidar(:,1),delta_yaw_degree); +Distance_meter = tag_pos_lidar(:,1); +T = table(Distance_meter,delta_x_meter,delta_y_meter,delta_z_meter,delta_r_degree,delta_p_degree,delta_yaw_degree) \ No newline at end of file diff --git a/matlab/new_preprocess/CCW1.mat b/matlab/new_preprocess/CCW1.mat new file mode 100644 index 0000000..82215f5 Binary files /dev/null and b/matlab/new_preprocess/CCW1.mat differ diff --git a/matlab/new_preprocess/big-3.mat b/matlab/new_preprocess/big-3.mat new file mode 100644 index 0000000..ca56690 Binary files /dev/null and b/matlab/new_preprocess/big-3.mat differ diff --git a/matlab/new_preprocess/createSE3.m b/matlab/new_preprocess/createSE3.m new file mode 100644 index 0000000..bab1bfd --- /dev/null +++ b/matlab/new_preprocess/createSE3.m @@ -0,0 +1,6 @@ +function [H] = createSE3(R, position) +%CREATESE3 Creates a 4x4 from a 3x3 rotation matrix and 3x1 position matrix +H = [R makeColumn(position); + zeros(1,3) 1]; +end + diff --git a/matlab/new_preprocess/loadpose.m b/matlab/new_preprocess/loadpose.m new file mode 100644 index 0000000..0584cb8 --- /dev/null +++ b/matlab/new_preprocess/loadpose.m @@ -0,0 +1,46 @@ +clear +file = load('big-3.mat'); +total_frames = file.big_3.Frames; +for k = 1: file.big_3.RigidBodies.Bodies + if strcmp(file.big_3.RigidBodies.Name(k), 'lidar') + lidar_pos = file.big_3.RigidBodies.Positions(k,:,:); + lidar_rot = file.big_3.RigidBodies.Rotations(k,:,:); + else + tag_pos = file.big_3.RigidBodies.Positions(k,:,:); + tag_rot = file.big_3.RigidBodies.Rotations(k,:,:); + end +end +invalid_num = 0; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos(:,:,m))) || any(isnan(lidar_rot(:,:,m))); + tag_invalid = any(isnan(tag_pos(:,:,m))) || any(isnan(tag_rot(:,:,m))); + if (lidar_invalid || tag_invalid) + lidar_pos(:,:,m) = zeros(1,3); + lidar_rot(:,:,m) = zeros(1,9); + tag_pos(:,:,m) = zeros(1,3); + tag_rot(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + end +end +lidar_pos_mean = sum(lidar_pos,3)/(total_frames - invalid_num); +lidar_rot_mean = sum(lidar_rot,3)/(total_frames - invalid_num); +tag_pos_mean = sum(tag_pos,3)/(total_frames - invalid_num); +tag_rot_mean = sum(tag_rot,3)/(total_frames - invalid_num); +lidar_rotm = reshape(lidar_rot_mean,3,3); +tag_rotm = reshape(tag_rot_mean,3,3); +world_H_tag = createSE3(tag_rotm, tag_pos_mean'); +world_H_lidar = createSE3(lidar_rotm, lidar_pos_mean'); +lidar_H_tag = world_H_lidar \ world_H_tag; +angles = rotm2eul(lidar_H_tag(1:3,1:3), 'ZYX'); +mocap_to_lidar_change_of_basis = [0 -1 0; 1 0 0; 0 0 1]; +new_basis = mocap_to_lidar_change_of_basis; +angles = fliplr(angles)'; +angles = flipud(new_basis*angles)'; +tag_rotm_lidar = angles; +tag_pos_lidar = new_basis*lidar_H_tag(1:3,4); +figure(1) +vector(1,:) = tag_rotm_lidar; +vector(2,:) = tag_pos_lidar/1000; +linespec='-' + +quiver3(zeros(2,1),zeros(2,1),zeros(2,1),vector(:,1), vector(:,2),vector(:,3),0,linespec) diff --git a/matlab/new_preprocess/main.m b/matlab/new_preprocess/main.m new file mode 100644 index 0000000..6b9e265 --- /dev/null +++ b/matlab/new_preprocess/main.m @@ -0,0 +1,305 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +% Files +mocap_path = "./"; +datasets = 1; + + + +%% Datasets +if datasets == 1 + mocap_name = "CCW1"; + mocap_files = load(mocap_path + mocap_name + ".mat"); + + distance(1,:) = [318,1834]; + distance(2,:) = [2792,5156]; + distance(3,:) = [5779,6880]; + distance(4,:) = [7422,8925]; + distance(5,:) = [9625,11170]; + distance(6,:) = [11850,13270]; + estimation_indices = 1:6; + +elseif datasets == 2 + mocap_name = "straight_front1"; + mocap_files = load(mocap_path + mocap_name + ".mat"); + + + distance(1,:) = [44, 2188]; + distance(2,:) = [2900, 3252]; + distance(3,:) = [4053, 4681]; + distance(4,:) = [5026, 5498]; + distance(5,:) = [6935, 8542]; + distance(6,:) = [8977, 9519]; + estimation_indices = 2:5; +end + +lt_estimate_path = mocap_path + ... + "predictions/mocap_prediction/" + ... + lower(mocap_name) + "-"; +% apriltag estimatation path +at_estimate_path = mocap_path + ... + "predictions/apriltag_prediction/" + ... + lower(mocap_name) + "-"; + +%% Frame assignment +for k = 1:mocap_files.(mocap_name).RigidBodies.Bodies + if strcmp(mocap_files.(mocap_name).RigidBodies.Name(k),'lidar') + lidar_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + lidar_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + tag_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + end +end + + +%% Remove invalid data points +n = 1; +invalid_num = 0; +total_frames = mocap_files.(mocap_name).Frames; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || ... + any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || ... + any(isnan(tag_rot_raw(:,:,m))); + + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end + +valid_frames = n - 1; +lidart = 1:valid_frames; +y = squeeze(lidar_pos(1, 1,:)); +figure(1); +scatter(lidart,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 2,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 3,:)); +figure(3); +scatter(p,q,'filled'); + + + +%% Frame conversion +H_L1L2 = eye(4); +H_T1T2 = eye(4); +H_L1L2(1:3, 1:3) = rotz(-90) * roty(180); +H_T1T2(1:3, 1:3) = rotz(-90) * roty(180); + + +%% Mocap data +num_mocap_data = size(distance, 1); +M_rpy_L2T2 = zeros(num_mocap_data, 3); +M_trans_L2T2 = zeros(num_mocap_data, 3); + + +for i = 1:num_mocap_data + % LiDAR 1 + L1_trans_mean = mean(lidar_pos(1, :, distance(i,1):distance(i,2)), 3); + L1_rot_mean = mean(lidar_rot(1, :, distance(i,1):distance(i,2)), 3); + + % Target 1 + T1_trans_mean = mean(tag_pos(1, :, distance(i,1):distance(i,2)), 3); + T1_rot_mean = mean(tag_rot(1, :, distance(i,1):distance(i,2)), 3); + + % Convert rotm from 1x9 to 3x3 + L1_rotm = reshape(L1_rot_mean, 3, 3); + T1_rotm = reshape(T1_rot_mean, 3, 3); + + % Construct H + H_W1T1 = createSE3(T1_rotm, T1_trans_mean'); + H_W1L1 = createSE3(L1_rotm, L1_trans_mean'); + + +% H_L2T2 = (H_WL1 * H_L1L2) \ (H_WT1 * H_T1T2); + H_L2T2 = (H_T1T2 * H_W1T1) / (H_L1L2 * H_W1L1); + + M_rpy_L2T2(i, :) = rad2deg(rotm2eul(H_L2T2(1:3,1:3), 'XYZ')); + M_trans_L2T2(i, :) = H_L2T2(1:3,4) ./ 1000; +end + +%% Estimated data +L_trans_L2T2 = zeros(length(estimation_indices), 3); +L_rpy_L2T2 = zeros(length(estimation_indices), 3); +A_trans_C2T2 = zeros(length(estimation_indices), 3); +A_rpy_C2T2 = zeros(length(estimation_indices), 3); +for i = estimation_indices + lt_current_path = lt_estimate_path + num2str(i) + "/"; + lt_estimate_file = dir(lt_current_path + "*.txt"); + lidart = dlmread(lt_current_path + lt_estimate_file.name, ',', 1, 0); + L_trans_L2T2(i,:) = mean(lidart(:, 4:6), 1); + L_rpy_L2T2(i,:) = rad2deg(mean(lidart(:, 7:9),1)); + + at_current_path = at_estimate_path + num2str(i) + "/"; + at_estimate_file = dir(at_current_path + "*april.txt"); + apriltag = dlmread(at_current_path + at_estimate_file.name, ',', 1, 0); + A_trans_C2T2(i,:) = mean(apriltag(:,3:5),1); + A_rpy_C2T2(i,:) = rad2deg(mean(apriltag(:,6:8),1)); +end +M_rpy_L2T2 +M_trans_L2T2 +L_rpy_L2T2 +L_trans_L2T2 + + +%% Results +Distance_meter = M_trans_L2T2(estimation_indices, 1); +d_x_meter = L_trans_L2T2(estimation_indices, 1) - ... + M_trans_L2T2(estimation_indices, 1); +d_y_meter = L_trans_L2T2(estimation_indices, 2) - ... + M_trans_L2T2(estimation_indices, 2); +d_z_meter = L_trans_L2T2(estimation_indices, 3) - ... + M_trans_L2T2(estimation_indices, 3); +d_r_degree = L_rpy_L2T2(estimation_indices, 1) - ... + M_trans_L2T2(estimation_indices, 1); +d_p_degree = L_rpy_L2T2(estimation_indices, 2) - ... + M_trans_L2T2(estimation_indices, 2); +d_h_degree = L_rpy_L2T2(estimation_indices, 3) - ... + M_trans_L2T2(estimation_indices, 3); + + +%% Tables +T = table(Distance_meter, ... + d_x_meter, d_y_meter, d_z_meter, ... + d_r_degree,d_p_degree,d_h_degree) + + +%% Plottings +figure(1); +plot(M_trans_L2T2(estimation_indices, 1), d_x_meter); + +figure(2); +plot(M_trans_L2T2(estimation_indices, 1), d_y_meter); + +figure(3); +plot(M_trans_L2T2(estimation_indices, 1), d_z_meter); + +figure(4); +plot(M_trans_L2T2(estimation_indices, 1), d_r_degree); + +figure(5); +plot(M_trans_L2T2(estimation_indices, 1), d_p_degree); + +figure(6); +plot(M_trans_L2T2(estimation_indices, 1), d_h_degree); + + +%% +num_data = 3; + +% LiDAR 1 +L1_trans_mean = mean(lidar_pos(1,:,distance(num_data,1):distance(num_data,2)),3)./1000; +L1_rot_mean = mean(lidar_rot(1,:,distance(num_data,1):distance(num_data,2)),3); + +% Target 1 +T1_trans_mean = mean(tag_pos(1,:,distance(num_data,1):distance(num_data,2)),3)./1000; +T1_rot_mean = mean(tag_rot(1,:,distance(num_data,1):distance(num_data,2)),3); + +% Convert rotm from 1x9 to 3x3 +L1_rotm = reshape(L1_rot_mean, 3, 3); +T1_rotm = reshape(T1_rot_mean, 3, 3); + +% Construct H +H_W1T1 = createSE3(T1_rotm, T1_trans_mean); +H_W1L1 = createSE3(L1_rotm, L1_trans_mean); + +% change basis +H_L1T1 = H_W1L1 \ H_W1T1; +H_W3W1 = eye(4); +H_W3W1(1:3, 1:3) = roty(180) * rotz(-90); + +H_W1L2 = (H_W1L1 * H_L1L2); +H_W1T2 = (H_W1T1 * H_T1T2); +H_L2T2 = H_W1L2 \ H_W1T2; + + + +M_rpy_L2T2(i, :) = rad2deg(rotm2eul(H_L2T2(1:3,1:3), 'XYZ')); +M_trans_L2T2(i, :) = H_L2T2(1:3,4) ./ 1000; + + +%% Testing +[axes_h, fig_h] = createFigHandleWithNumber(5, 100,"frames", 1, 1); + +% Frame +W1 = eye(4); % Frame of LiDAR Device + + +W2 = eye(4); +W2(1:3, 1:3) = rotz(-90); +W2(1:3, 4) = 1; + +W3 = eye(4); +W3(1:3, 1:3) = rotx(180) * rotz(-90); +W3(1:3, 4) = 2; + + +cur_fig = axes_h(1); +plotColoredOriginAxisWithText(cur_fig, "W1", W1, 0.5) +plotColoredOriginAxisWithText(cur_fig, "W2", W2, 0.5) +plotColoredOriginAxisWithText(cur_fig, "W3", W3, 0.5) + +showCurrentPlot(cur_fig, "Frame system", [-40 30], 1) + + + +%% + +% Frame +W3 = eye(4); % Frame of LiDAR Device +W1 = eye(4); +W1(1:3, 1:3) = rotx(180) * rotz(-90); +% W1(1:3, 1:3) = roty(180); +W1(1:3, 4) = 1; + + +cur_fig = axes_h(1); +plotColoredOriginAxisWithText(cur_fig, "W3", W3, 0.5) +plotColoredOriginAxisWithText(cur_fig, "W1", W1, 0.5) +showCurrentPlot(cur_fig, "Frame system", [-40 30], 1) + + +cur_fig = axes_h(2); +plotColoredOriginAxisWithText(cur_fig, "Origin", eye(4), 0.5) +plotColoredOriginAxisWithText(cur_fig, "Mocap", W1, 0.5) +plotColoredOriginAxisWithText(cur_fig, "LiDAR", H_W1L1 * W1, 0.5) +plotColoredOriginAxisWithText(cur_fig, "Tag", H_W1T1 * W1, 0.5) +showCurrentPlot(cur_fig, "Mcap Frames", [-40 30], 1) + + + +cur_fig = axes_h(3); +plotColoredOriginAxisWithText(cur_fig, "Origin", W1, 0.5) +plotColoredOriginAxisWithText(cur_fig, "LiDAR", H_W1L2 * W1, 0.5) +plotColoredOriginAxisWithText(cur_fig, "Tag", H_W1T2 * W1, 0.5) +showCurrentPlot(cur_fig, "LiDAR Frames", [-40 30], 1) + + + +% reloadCurrentPlot(cur_fig) +% set(cur_fig, 'ZDir','reverse') +% set(cur_fig, 'ZDir','normal') + +disp("Done") \ No newline at end of file diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_april.txt new file mode 100644 index 0000000..ef8fdab --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_april.txt @@ -0,0 +1,24 @@ +iter,id,x,y,z,r,p,y +1,1,2.69195,-0.305796,-0.189874,0.992814,0.566264,-0.0560721 +2,1,2.69177,-0.305823,-0.189933,0.992729,0.56626,-0.0557825 +3,1,2.69188,-0.305806,-0.189784,0.992832,0.566239,-0.0560231 +8,1,2.69187,-0.305837,-0.18974,0.992505,0.566133,-0.0553982 +27,1,2.69175,-0.305783,-0.189603,0.992536,0.566218,-0.0555031 +38,1,2.6917,-0.305848,-0.18952,0.992787,0.566295,-0.0557541 +39,1,2.69173,-0.305837,-0.189463,0.992702,0.566246,-0.0555253 +51,1,2.69149,-0.305846,-0.189352,0.992657,0.566188,-0.0554048 +66,1,2.69164,-0.305811,-0.189349,0.99256,0.566264,-0.0554289 +80,1,2.69175,-0.30582,-0.189349,0.992799,0.566421,-0.0559073 +82,1,2.69176,-0.305806,-0.189393,0.992551,0.566403,-0.05526 +86,1,2.69137,-0.305802,-0.189267,0.99267,0.566764,-0.0555737 +100,1,2.69183,-0.305787,-0.189394,0.992665,0.566388,-0.0558551 +106,1,2.69188,-0.305846,-0.189409,0.992586,0.566298,-0.0558141 +107,1,2.69164,-0.305818,-0.189522,0.992734,0.566313,-0.0556944 +122,1,2.69153,-0.305785,-0.189292,0.992631,0.566729,-0.0554694 +132,1,2.69169,-0.305798,-0.189521,0.992563,0.566422,-0.0551896 +134,1,2.69172,-0.305811,-0.189536,0.992496,0.56632,-0.0549878 +158,1,2.69172,-0.305732,-0.189556,0.992643,0.566476,-0.0556499 +169,1,2.69192,-0.305854,-0.189374,0.992658,0.566401,-0.0554609 +196,1,2.69175,-0.305797,-0.189374,0.992637,0.566426,-0.0558348 +201,1,2.69185,-0.305843,-0.189517,0.99259,0.566212,-0.055253 +202,1,2.69156,-0.305828,-0.189413,0.992615,0.566539,-0.0554878 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_other.txt new file mode 100644 index 0000000..cebbe70 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-1/pose_other.txt @@ -0,0 +1,24 @@ +iter,id,x,y,z,r,p,y +1,1,0.304229,0.189253,2.71661,2.76295,0.433108,-0.892236 +2,1,0.304277,0.189333,2.71647,2.76323,0.433271,-0.892293 +3,1,0.304247,0.189177,2.71653,2.76306,0.433162,-0.892303 +8,1,0.304294,0.189143,2.71657,2.76356,0.433337,-0.892251 +27,1,0.304236,0.189006,2.71642,2.76342,0.433364,-0.892213 +38,1,0.304303,0.18892,2.7164,2.76325,0.433341,-0.892352 +39,1,0.304296,0.188872,2.71641,2.76347,0.433443,-0.892376 +51,1,0.304301,0.188754,2.71618,2.76357,0.433441,-0.892384 +66,1,0.304238,0.188724,2.71626,2.76337,0.433426,-0.8922 +80,1,0.304254,0.188748,2.7163,2.76303,0.433427,-0.89225 +82,1,0.30424,0.188781,2.71637,2.76346,0.433671,-0.892224 +86,1,0.304233,0.188655,2.71595,2.76299,0.433816,-0.892108 +100,1,0.30423,0.188782,2.7165,2.76301,0.433293,-0.892137 +106,1,0.304277,0.188778,2.71657,2.76301,0.433171,-0.892072 +107,1,0.304264,0.188921,2.71628,2.76326,0.433403,-0.892305 +122,1,0.304213,0.18867,2.71614,2.76305,0.433799,-0.892103 +132,1,0.304248,0.188915,2.71638,2.76353,0.433697,-0.892273 +134,1,0.304265,0.188927,2.71645,2.76374,0.433691,-0.892311 +158,1,0.304164,0.188926,2.71641,2.76306,0.433438,-0.892132 +169,1,0.304273,0.188735,2.71656,2.76325,0.433511,-0.892221 +196,1,0.304224,0.188745,2.7164,2.76294,0.433303,-0.892073 +201,1,0.304299,0.188912,2.71659,2.76364,0.433487,-0.892354 +202,1,0.304257,0.188785,2.71622,2.76315,0.433601,-0.89214 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_april.txt new file mode 100644 index 0000000..094507d --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_april.txt @@ -0,0 +1,220 @@ +iter,id,x,y,z,r,p,y +0,1,5.49367,-0.592613,-0.660583,1.0251,0.560086,-0.0919556 +1,1,5.49259,-0.592664,-0.661782,1.02533,0.560816,-0.0925958 +2,1,5.49281,-0.592421,-0.661663,1.02523,0.560522,-0.0921725 +3,1,5.49365,-0.592819,-0.661449,1.02521,0.560313,-0.0917525 +4,1,5.49515,-0.59285,-0.660612,1.02527,0.559917,-0.0930344 +5,1,5.49314,-0.592746,-0.660862,1.02539,0.559921,-0.0921761 +6,1,5.49348,-0.59268,-0.661563,1.02513,0.560294,-0.0920295 +7,1,5.49336,-0.592647,-0.661512,1.02503,0.559975,-0.0922601 +8,1,5.49352,-0.592867,-0.661137,1.02497,0.559738,-0.0920594 +9,1,5.49349,-0.592705,-0.660628,1.02553,0.560506,-0.0929872 +10,1,5.49252,-0.592631,-0.66086,1.02503,0.55997,-0.0918424 +11,1,5.49268,-0.592685,-0.661323,1.02485,0.560087,-0.0910536 +12,1,5.49288,-0.592576,-0.661522,1.02526,0.559914,-0.0924214 +13,1,5.49354,-0.592902,-0.660985,1.02507,0.560159,-0.0921998 +14,1,5.49209,-0.592782,-0.660753,1.02519,0.560147,-0.0914292 +15,1,5.49369,-0.592813,-0.660631,1.0253,0.560483,-0.0928683 +16,1,5.49195,-0.592679,-0.660873,1.0251,0.560343,-0.0915916 +17,1,5.49273,-0.59256,-0.6614,1.02503,0.560026,-0.0921971 +18,1,5.49349,-0.592688,-0.661048,1.02515,0.560131,-0.0920587 +19,1,5.49387,-0.592955,-0.660748,1.02523,0.560431,-0.0920401 +20,1,5.49284,-0.592785,-0.66063,1.02516,0.560198,-0.0920922 +21,1,5.49264,-0.592751,-0.661054,1.02491,0.559883,-0.0911651 +22,1,5.49317,-0.592745,-0.661111,1.02533,0.55994,-0.0917937 +23,1,5.49245,-0.592743,-0.660897,1.0251,0.56018,-0.0915217 +24,1,5.49189,-0.592763,-0.660668,1.02496,0.56063,-0.090982 +25,1,5.49259,-0.592844,-0.660838,1.02536,0.560442,-0.0915417 +26,1,5.49393,-0.592819,-0.661012,1.02508,0.559992,-0.0921248 +27,1,5.49252,-0.592577,-0.661111,1.02473,0.560212,-0.0909337 +28,1,5.49223,-0.592675,-0.66087,1.02518,0.560265,-0.0915724 +29,1,5.49261,-0.592795,-0.66068,1.02469,0.560222,-0.0906294 +30,1,5.49232,-0.592734,-0.660715,1.02478,0.560158,-0.0905373 +31,1,5.4922,-0.592842,-0.660605,1.02509,0.560293,-0.0919271 +32,1,5.4929,-0.592901,-0.660827,1.02524,0.560431,-0.0914766 +33,1,5.49309,-0.592891,-0.660878,1.0252,0.560221,-0.0911631 +34,1,5.49248,-0.592852,-0.66071,1.02499,0.560025,-0.0908913 +35,1,5.49304,-0.592841,-0.660752,1.0254,0.56003,-0.0914624 +36,1,5.4933,-0.592861,-0.660734,1.02523,0.55983,-0.0912321 +37,1,5.49314,-0.592895,-0.660674,1.02537,0.560099,-0.0921024 +38,1,5.49301,-0.592922,-0.66079,1.02504,0.560209,-0.0908383 +39,1,5.49197,-0.592755,-0.660667,1.02513,0.560543,-0.0909191 +40,1,5.49266,-0.592861,-0.660654,1.02506,0.560485,-0.0905467 +41,1,5.49286,-0.592879,-0.660585,1.02526,0.560432,-0.0918722 +42,1,5.49351,-0.592826,-0.660663,1.02545,0.560457,-0.0915911 +43,1,5.49313,-0.59272,-0.660686,1.0253,0.560291,-0.0924954 +44,1,5.49349,-0.593003,-0.660856,1.02547,0.560288,-0.0918393 +45,1,5.49263,-0.592677,-0.660917,1.02513,0.560239,-0.091716 +46,1,5.4927,-0.592509,-0.660855,1.0254,0.5606,-0.0924889 +47,1,5.49192,-0.592467,-0.659854,1.02531,0.560338,-0.0908675 +48,1,5.49093,-0.592442,-0.663091,1.02531,0.56124,-0.0920129 +49,1,5.49559,-0.592956,-0.663076,1.0257,0.560604,-0.0936895 +50,1,5.49438,-0.593333,-0.659781,1.02525,0.560179,-0.0916364 +51,1,5.4939,-0.593608,-0.659178,1.02524,0.559875,-0.091679 +52,1,5.49285,-0.593434,-0.66012,1.02518,0.56009,-0.0919872 +53,1,5.49315,-0.593427,-0.660907,1.02505,0.56061,-0.0913154 +54,1,5.49186,-0.593648,-0.660673,1.02487,0.560284,-0.0908572 +55,1,5.49308,-0.593881,-0.661304,1.02523,0.560416,-0.0912237 +56,1,5.49734,-0.593601,-0.659838,1.02521,0.559336,-0.0935375 +57,1,5.49154,-0.592972,-0.658177,1.02499,0.560696,-0.092256 +58,1,5.49133,-0.593002,-0.660641,1.02534,0.56069,-0.0915766 +59,1,5.4917,-0.592851,-0.663917,1.02563,0.560162,-0.0927615 +60,1,5.49601,-0.593472,-0.663562,1.02566,0.559952,-0.0935572 +61,1,5.49407,-0.592841,-0.657293,1.02521,0.560158,-0.0915625 +62,1,5.49138,-0.592311,-0.658845,1.02516,0.560735,-0.0910977 +63,1,5.49136,-0.591769,-0.662934,1.02589,0.561211,-0.0919928 +64,1,5.49085,-0.591404,-0.666809,1.02605,0.561925,-0.0925371 +65,1,5.49591,-0.592063,-0.666133,1.02616,0.560868,-0.0933472 +66,1,5.4942,-0.592013,-0.661496,1.02582,0.560147,-0.091814 +67,1,5.49304,-0.592417,-0.660391,1.02552,0.560435,-0.0920904 +68,1,5.49244,-0.591959,-0.661813,1.02618,0.560881,-0.0928758 +69,1,5.49299,-0.59215,-0.663946,1.02582,0.560631,-0.0930297 +70,1,5.49346,-0.592109,-0.66447,1.0261,0.560679,-0.0934617 +71,1,5.49304,-0.591826,-0.663394,1.02588,0.561096,-0.0927893 +72,1,5.49345,-0.591977,-0.662559,1.02564,0.560333,-0.0924293 +73,1,5.49305,-0.591995,-0.662166,1.02542,0.560825,-0.091191 +74,1,5.49179,-0.591707,-0.663224,1.02581,0.561425,-0.0925325 +75,1,5.49292,-0.591693,-0.663939,1.02575,0.560893,-0.0929668 +76,1,5.49282,-0.591705,-0.664084,1.02574,0.561203,-0.0925747 +77,1,5.49402,-0.592073,-0.663131,1.02629,0.56087,-0.0931542 +78,1,5.4919,-0.592008,-0.662241,1.02542,0.560932,-0.0913186 +79,1,5.49352,-0.59207,-0.663173,1.02603,0.560676,-0.0930407 +80,1,5.49222,-0.591971,-0.663692,1.02548,0.561047,-0.0914638 +81,1,5.49323,-0.592145,-0.663724,1.02557,0.560614,-0.0922203 +82,1,5.49351,-0.592245,-0.662652,1.02554,0.560502,-0.0924833 +83,1,5.49282,-0.59228,-0.662431,1.02548,0.560743,-0.0916286 +84,1,5.49232,-0.592138,-0.662636,1.02508,0.560711,-0.0918068 +85,1,5.49261,-0.592303,-0.662958,1.02568,0.560592,-0.091894 +86,1,5.49268,-0.592208,-0.663088,1.02601,0.560694,-0.0922833 +87,1,5.49337,-0.59231,-0.663142,1.02649,0.560452,-0.0941926 +88,1,5.49348,-0.592292,-0.662747,1.02598,0.560307,-0.0931319 +89,1,5.49314,-0.592348,-0.662496,1.02557,0.560553,-0.0925026 +90,1,5.49303,-0.592304,-0.662875,1.0259,0.560646,-0.0924835 +91,1,5.49243,-0.592196,-0.663091,1.02577,0.560931,-0.0920373 +92,1,5.49266,-0.592054,-0.663586,1.02605,0.560757,-0.0932433 +93,1,5.49318,-0.592244,-0.662903,1.02585,0.560655,-0.0929854 +94,1,5.49264,-0.592138,-0.662976,1.02602,0.560422,-0.0927901 +95,1,5.4929,-0.592314,-0.66298,1.02603,0.560605,-0.0927961 +96,1,5.4927,-0.592174,-0.662919,1.02611,0.560441,-0.0929076 +97,1,5.49286,-0.592347,-0.662768,1.02582,0.560512,-0.0928528 +98,1,5.49372,-0.592439,-0.662761,1.02546,0.560535,-0.0921201 +99,1,5.49256,-0.592485,-0.662503,1.02517,0.560727,-0.0908096 +100,1,5.49199,-0.592395,-0.662288,1.02521,0.560778,-0.0911071 +101,1,5.49259,-0.592496,-0.663049,1.02589,0.560744,-0.0924896 +102,1,5.49345,-0.592335,-0.66315,1.02586,0.560731,-0.0920664 +103,1,5.49241,-0.592316,-0.662333,1.02546,0.560864,-0.0914787 +104,1,5.49235,-0.592342,-0.662599,1.02541,0.560693,-0.0916462 +105,1,5.49291,-0.592373,-0.663011,1.02592,0.560605,-0.0922692 +106,1,5.49434,-0.592417,-0.663021,1.02596,0.560137,-0.0937038 +107,1,5.49385,-0.592402,-0.662744,1.02553,0.560139,-0.0919579 +108,1,5.49202,-0.592439,-0.662586,1.02533,0.560653,-0.0922507 +109,1,5.49458,-0.59254,-0.662855,1.02595,0.560435,-0.0928588 +110,1,5.49355,-0.592444,-0.662724,1.0256,0.560422,-0.0922786 +111,1,5.49239,-0.592515,-0.662378,1.02525,0.560516,-0.0915426 +112,1,5.49321,-0.592521,-0.662844,1.02604,0.560269,-0.0936679 +113,1,5.4932,-0.592614,-0.662651,1.02554,0.560555,-0.0925161 +114,1,5.49384,-0.592157,-0.661469,1.02538,0.560554,-0.0920147 +115,1,5.49179,-0.592912,-0.662433,1.02542,0.560822,-0.0922749 +116,1,5.49331,-0.592489,-0.662865,1.02528,0.560741,-0.0913538 +117,1,5.49331,-0.592929,-0.660009,1.02535,0.560062,-0.0921903 +118,1,5.49337,-0.593004,-0.659962,1.02498,0.5599,-0.0922137 +119,1,5.4922,-0.592717,-0.660751,1.02503,0.560571,-0.0902549 +120,1,5.49242,-0.592821,-0.663319,1.02572,0.560324,-0.0924958 +121,1,5.49422,-0.592617,-0.661844,1.0255,0.560309,-0.0931413 +122,1,5.4936,-0.592923,-0.660783,1.02498,0.559946,-0.0920082 +123,1,5.49381,-0.592958,-0.660374,1.02522,0.560579,-0.0921506 +124,1,5.49275,-0.592748,-0.660888,1.02535,0.560561,-0.0925021 +125,1,5.49266,-0.592818,-0.661376,1.0252,0.560261,-0.0918409 +126,1,5.4935,-0.592718,-0.661548,1.02529,0.560172,-0.0928026 +127,1,5.493,-0.592844,-0.66192,1.02532,0.560125,-0.0924134 +128,1,5.49309,-0.592767,-0.660736,1.02525,0.560006,-0.0917766 +129,1,5.49308,-0.5929,-0.660437,1.025,0.560226,-0.0915161 +130,1,5.49335,-0.592918,-0.6609,1.02515,0.559843,-0.0915558 +131,1,5.49315,-0.592991,-0.661751,1.02512,0.560168,-0.0924584 +132,1,5.49402,-0.592878,-0.661451,1.0251,0.559957,-0.0918063 +133,1,5.49345,-0.592966,-0.6606,1.02542,0.560512,-0.0920991 +134,1,5.49291,-0.592858,-0.660653,1.02539,0.560531,-0.0922784 +135,1,5.49288,-0.592823,-0.661046,1.02526,0.560292,-0.0921833 +136,1,5.49337,-0.592686,-0.661403,1.02527,0.559902,-0.0925038 +137,1,5.49379,-0.59289,-0.661065,1.0257,0.560457,-0.0924789 +138,1,5.49202,-0.592771,-0.660894,1.02522,0.560652,-0.0918815 +139,1,5.49276,-0.592801,-0.660544,1.02515,0.560282,-0.0918554 +140,1,5.49281,-0.592885,-0.660699,1.02522,0.560466,-0.0910716 +141,1,5.49212,-0.592867,-0.661003,1.02472,0.560621,-0.0911065 +142,1,5.4926,-0.59282,-0.661238,1.025,0.560535,-0.0915271 +143,1,5.49338,-0.592902,-0.660731,1.02539,0.560205,-0.0918287 +144,1,5.49304,-0.592902,-0.660498,1.02513,0.560332,-0.0919402 +145,1,5.49267,-0.592864,-0.660883,1.02553,0.560234,-0.0918212 +146,1,5.49181,-0.592707,-0.660886,1.02502,0.560976,-0.0915372 +147,1,5.494,-0.593,-0.66119,1.02538,0.559938,-0.092657 +148,1,5.49251,-0.592859,-0.660791,1.02542,0.560586,-0.0913749 +148,28,33.8773,3.00595,11.261,1.43264,0.199394,-1.10442 +149,1,5.49413,-0.592925,-0.660995,1.02541,0.559611,-0.0927738 +150,1,5.49281,-0.59286,-0.660803,1.02532,0.560573,-0.0913093 +151,1,5.49222,-0.592781,-0.661056,1.02532,0.560749,-0.091234 +152,1,5.49307,-0.592838,-0.661021,1.02564,0.560414,-0.0930453 +153,1,5.49355,-0.593009,-0.661051,1.0252,0.560376,-0.091967 +154,1,5.49271,-0.592758,-0.660854,1.02506,0.560639,-0.0916623 +155,1,5.49353,-0.593004,-0.660789,1.0252,0.560188,-0.0920207 +156,1,5.49287,-0.5929,-0.660826,1.02538,0.560077,-0.0917763 +157,1,5.49326,-0.59281,-0.660879,1.02507,0.560058,-0.0917529 +158,1,5.49387,-0.592937,-0.660883,1.02538,0.560393,-0.0921585 +159,1,5.49227,-0.592958,-0.660826,1.025,0.560804,-0.0904644 +160,1,5.49258,-0.592981,-0.660759,1.0254,0.561022,-0.0915161 +161,1,5.493,-0.592949,-0.66083,1.0256,0.560565,-0.0917852 +162,1,5.49354,-0.592873,-0.66082,1.02556,0.56017,-0.0923466 +163,1,5.49344,-0.592986,-0.660765,1.02542,0.560212,-0.0920016 +164,1,5.49256,-0.592904,-0.660942,1.0252,0.560573,-0.0909953 +165,1,5.49274,-0.592924,-0.66087,1.02551,0.560456,-0.0918861 +166,1,5.49357,-0.59297,-0.660755,1.02558,0.560663,-0.0926089 +167,1,5.4935,-0.593016,-0.660705,1.02528,0.560536,-0.0914079 +168,1,5.49324,-0.592892,-0.660696,1.0254,0.560497,-0.0923535 +169,1,5.49313,-0.592956,-0.660909,1.02543,0.56067,-0.091654 +170,1,5.49292,-0.592952,-0.660598,1.02518,0.560437,-0.0917534 +171,1,5.49345,-0.592892,-0.660653,1.0253,0.560518,-0.0923088 +172,1,5.49388,-0.59283,-0.660774,1.02491,0.560397,-0.0916204 +173,1,5.49317,-0.592922,-0.660811,1.02554,0.56079,-0.0917045 +174,1,5.49307,-0.59291,-0.660769,1.02527,0.56048,-0.0915716 +175,1,5.49357,-0.592991,-0.660644,1.02548,0.560435,-0.0924916 +176,1,5.49389,-0.593073,-0.66073,1.02542,0.560365,-0.0915508 +177,1,5.48611,-0.59221,-0.659251,1.02511,0.56062,-0.0920683 +178,1,5.48737,-0.592208,-0.659411,1.02521,0.560562,-0.0932154 +179,1,5.48637,-0.592298,-0.659531,1.02533,0.56041,-0.0917599 +180,1,5.487,-0.592218,-0.659392,1.02524,0.560724,-0.0912057 +181,1,5.48733,-0.59236,-0.659393,1.02547,0.560826,-0.0924529 +182,1,5.48842,-0.592388,-0.659596,1.02594,0.56015,-0.0928956 +183,1,5.48664,-0.592336,-0.659387,1.02565,0.560958,-0.0913359 +184,1,5.48777,-0.592396,-0.65969,1.025,0.560803,-0.0909025 +185,1,5.48704,-0.592447,-0.659583,1.02503,0.560696,-0.0905041 +186,1,5.48751,-0.592313,-0.659532,1.02513,0.560776,-0.0922334 +187,1,5.48681,-0.592533,-0.659558,1.02527,0.561002,-0.0905039 +188,1,5.48779,-0.592465,-0.659744,1.02533,0.560706,-0.0913777 +189,1,5.48736,-0.592254,-0.659676,1.0252,0.561036,-0.0907723 +190,1,5.48675,-0.592306,-0.65946,1.02521,0.560974,-0.0907988 +191,1,5.48745,-0.592435,-0.659578,1.02496,0.560578,-0.0914498 +192,1,5.48636,-0.592232,-0.659259,1.02508,0.560611,-0.0922245 +193,1,5.4867,-0.592409,-0.659385,1.02495,0.560702,-0.09116 +194,1,5.4871,-0.592362,-0.659525,1.0249,0.560572,-0.0903001 +195,1,5.48649,-0.592172,-0.659383,1.02515,0.560865,-0.0915375 +196,1,5.48742,-0.5924,-0.659393,1.0255,0.560324,-0.0920675 +197,1,5.48722,-0.592268,-0.659217,1.02541,0.560367,-0.0933775 +198,1,5.4877,-0.592335,-0.659514,1.02545,0.560716,-0.0918565 +199,1,5.48694,-0.592472,-0.659596,1.02506,0.560208,-0.0913163 +200,1,5.48654,-0.592222,-0.659397,1.02537,0.560671,-0.0926617 +201,1,5.48728,-0.59239,-0.659593,1.02493,0.559977,-0.0901282 +202,1,5.4874,-0.59233,-0.65936,1.02544,0.559967,-0.0927305 +203,1,5.48625,-0.592154,-0.659201,1.02541,0.560138,-0.092939 +204,1,5.48714,-0.592296,-0.659605,1.02576,0.559975,-0.0928968 +205,1,5.486,-0.592242,-0.659451,1.02569,0.560592,-0.0924391 +206,1,5.48773,-0.592351,-0.659453,1.02522,0.560371,-0.0921968 +207,1,5.486,-0.592071,-0.659183,1.02563,0.560712,-0.0922856 +208,1,5.48613,-0.592158,-0.659163,1.02547,0.560796,-0.0925258 +209,1,5.48718,-0.592247,-0.659627,1.02491,0.560632,-0.0920283 +210,1,5.48736,-0.592367,-0.659581,1.02516,0.559974,-0.0915063 +211,1,5.48685,-0.59232,-0.659444,1.02499,0.560745,-0.0919617 +212,1,5.48783,-0.592328,-0.659498,1.02549,0.560288,-0.0930398 +213,1,5.48678,-0.592194,-0.659253,1.0252,0.560263,-0.091922 +214,1,5.48594,-0.592328,-0.659239,1.02507,0.560354,-0.0915728 +215,1,5.48599,-0.59225,-0.659243,1.02505,0.560554,-0.0919701 +216,1,5.48623,-0.592112,-0.659134,1.02519,0.560578,-0.0930016 +217,1,5.48764,-0.592337,-0.659114,1.02538,0.560055,-0.0926158 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_other.txt new file mode 100644 index 0000000..1c51f1d --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-2/pose_other.txt @@ -0,0 +1,220 @@ +iter,id,x,y,z,r,p,y +0,1,0.59341,0.662596,5.54413,2.7537,0.41393,-0.915722 +1,1,0.59343,0.663769,5.54281,2.75274,0.414293,-0.915446 +2,1,0.593181,0.663647,5.54297,2.75328,0.414304,-0.915605 +3,1,0.593585,0.663436,5.54384,2.75379,0.414391,-0.915819 +4,1,0.593639,0.662618,5.54554,2.75295,0.413235,-0.915576 +5,1,0.593543,0.662877,5.54361,2.75375,0.413781,-0.916 +6,1,0.593436,0.663539,5.54361,2.75349,0.414171,-0.915625 +7,1,0.593424,0.663509,5.54371,2.75344,0.413648,-0.915551 +8,1,0.59364,0.663131,5.54376,2.75382,0.413635,-0.915674 +9,1,0.593459,0.662603,5.54353,2.75274,0.413969,-0.91564 +10,1,0.593384,0.662836,5.54254,2.75392,0.414068,-0.915738 +11,1,0.593447,0.663306,5.54285,2.75439,0.414493,-0.915771 +12,1,0.593331,0.663499,5.54301,2.75346,0.413679,-0.915751 +13,1,0.593663,0.662967,5.54365,2.75347,0.413977,-0.915575 +14,1,0.593547,0.662737,5.54224,2.75418,0.414459,-0.915976 +15,1,0.593595,0.662634,5.54397,2.75279,0.413865,-0.915477 +16,1,0.593436,0.662854,5.54198,2.75394,0.414553,-0.915774 +17,1,0.593325,0.663385,5.54295,2.75349,0.413787,-0.915566 +18,1,0.59345,0.663034,5.5436,2.75367,0.414081,-0.91573 +19,1,0.593705,0.662718,5.54387,2.7535,0.414393,-0.915699 +20,1,0.593567,0.662632,5.54312,2.75359,0.414052,-0.915715 +21,1,0.593529,0.663053,5.54291,2.75449,0.414268,-0.915889 +22,1,0.593513,0.663098,5.54337,2.75405,0.414099,-0.916049 +23,1,0.593478,0.662853,5.54231,2.75407,0.414505,-0.915835 +24,1,0.593509,0.662633,5.54184,2.75418,0.415113,-0.91573 +25,1,0.593611,0.662822,5.54276,2.75394,0.414678,-0.915997 +26,1,0.593562,0.662977,5.54389,2.75365,0.413946,-0.915668 +27,1,0.593317,0.663071,5.54245,2.75438,0.414709,-0.915646 +28,1,0.593442,0.662856,5.54242,2.75396,0.414439,-0.915862 +29,1,0.593549,0.662651,5.54264,2.75462,0.414854,-0.915718 +30,1,0.593502,0.662701,5.54249,2.75479,0.41485,-0.915875 +31,1,0.593616,0.662597,5.54242,2.75363,0.414218,-0.915658 +32,1,0.593703,0.662849,5.54336,2.75401,0.414591,-0.915942 +33,1,0.593681,0.66289,5.54343,2.75442,0.414648,-0.916088 +34,1,0.593615,0.66269,5.5426,2.75465,0.414624,-0.916001 +35,1,0.593617,0.662748,5.54326,2.75435,0.41442,-0.916235 +36,1,0.59365,0.66274,5.54369,2.75456,0.414252,-0.916201 +37,1,0.593695,0.662692,5.5436,2.75371,0.413979,-0.915953 +38,1,0.593703,0.662792,5.54327,2.75464,0.414802,-0.916036 +39,1,0.593539,0.66267,5.54224,2.75438,0.415045,-0.915979 +40,1,0.593645,0.662655,5.54296,2.75468,0.415173,-0.916049 +41,1,0.593666,0.66259,5.54319,2.75365,0.414391,-0.9158 +42,1,0.593606,0.662659,5.5438,2.75392,0.414645,-0.916063 +43,1,0.593494,0.662682,5.54333,2.75325,0.413972,-0.915679 +44,1,0.593784,0.662855,5.54379,2.75384,0.414376,-0.916062 +45,1,0.593452,0.66291,5.54289,2.75382,0.414283,-0.915775 +46,1,0.593267,0.662834,5.54278,2.75306,0.414283,-0.915658 +47,1,0.593228,0.661825,5.54205,2.75452,0.414964,-0.916194 +48,1,0.593223,0.665108,5.54124,2.75308,0.415011,-0.915535 +49,1,0.593733,0.665085,5.54594,2.75212,0.413582,-0.915528 +50,1,0.594103,0.661762,5.54453,2.754,0.414383,-0.915951 +51,1,0.59442,0.661196,5.54443,2.75416,0.41398,-0.916051 +52,1,0.594226,0.662123,5.54328,2.75367,0.413952,-0.915769 +53,1,0.594222,0.662921,5.54355,2.75394,0.414779,-0.915725 +54,1,0.594402,0.662641,5.54191,2.75444,0.414834,-0.91578 +55,1,0.594652,0.663294,5.54326,2.75423,0.414834,-0.915997 +56,1,0.594381,0.661834,5.5476,2.75291,0.412511,-0.915549 +57,1,0.593719,0.660129,5.54146,2.75298,0.414369,-0.915262 +58,1,0.593757,0.662612,5.54137,2.75376,0.414903,-0.915872 +59,1,0.593636,0.665939,5.54213,2.75323,0.413759,-0.915959 +60,1,0.594236,0.665558,5.54627,2.75264,0.413161,-0.915749 +61,1,0.593587,0.659236,5.544,2.75398,0.414417,-0.915905 +62,1,0.593127,0.66087,5.54194,2.75405,0.414958,-0.915881 +63,1,0.592544,0.664938,5.54169,2.75324,0.415151,-0.916097 +64,1,0.592176,0.668838,5.54121,2.75246,0.415506,-0.915851 +65,1,0.592848,0.668157,5.54653,2.7523,0.414026,-0.915968 +66,1,0.592766,0.663471,5.5443,2.75406,0.414453,-0.91645 +67,1,0.593191,0.662381,5.5433,2.75351,0.414349,-0.915957 +68,1,0.59276,0.663841,5.54296,2.75284,0.414411,-0.916224 +69,1,0.592953,0.665985,5.54362,2.75271,0.413942,-0.91588 +70,1,0.592923,0.666523,5.54423,2.7524,0.413773,-0.915997 +71,1,0.592598,0.665401,5.54332,2.75266,0.414609,-0.915859 +72,1,0.592725,0.664536,5.54352,2.75337,0.414193,-0.915998 +73,1,0.592755,0.664154,5.54316,2.75407,0.415257,-0.916065 +74,1,0.59247,0.665219,5.54203,2.75259,0.414994,-0.915743 +75,1,0.592484,0.665966,5.54346,2.75254,0.414176,-0.915726 +76,1,0.592474,0.666087,5.54316,2.75265,0.414719,-0.915725 +77,1,0.592868,0.665156,5.54455,2.75262,0.414263,-0.916219 +78,1,0.592759,0.664216,5.542,2.75381,0.415237,-0.915944 +79,1,0.592829,0.66516,5.5438,2.75266,0.414126,-0.916016 +80,1,0.592742,0.665696,5.54252,2.75366,0.415207,-0.91593 +81,1,0.592927,0.665736,5.5437,2.75327,0.414356,-0.915888 +82,1,0.593016,0.664651,5.5438,2.75314,0.414172,-0.91582 +83,1,0.593072,0.664451,5.54324,2.75375,0.41484,-0.916004 +84,1,0.592918,0.664648,5.54265,2.75347,0.414589,-0.915552 +85,1,0.593083,0.664965,5.54301,2.75362,0.414604,-0.916123 +86,1,0.59297,0.665079,5.54293,2.75336,0.414636,-0.916285 +87,1,0.593087,0.665152,5.54376,2.75208,0.413428,-0.916195 +88,1,0.593077,0.664757,5.54395,2.75284,0.413706,-0.916089 +89,1,0.593121,0.664496,5.54344,2.75311,0.414209,-0.915823 +90,1,0.593095,0.664893,5.54353,2.75318,0.414347,-0.916134 +91,1,0.592978,0.665104,5.5428,2.75337,0.414863,-0.91607 +92,1,0.592829,0.665598,5.54298,2.75258,0.414127,-0.916002 +93,1,0.593014,0.664902,5.54347,2.75273,0.414106,-0.915898 +94,1,0.592912,0.664979,5.543,2.7531,0.414068,-0.916212 +95,1,0.593074,0.664966,5.54315,2.75295,0.414241,-0.916139 +96,1,0.592961,0.664934,5.54317,2.75302,0.414005,-0.916261 +97,1,0.593126,0.664775,5.54324,2.75292,0.414025,-0.915961 +98,1,0.593207,0.664757,5.54399,2.7534,0.414397,-0.915849 +99,1,0.593278,0.66452,5.54303,2.75429,0.415166,-0.915965 +100,1,0.593176,0.664293,5.54234,2.75403,0.415087,-0.915877 +101,1,0.593286,0.665069,5.54306,2.75314,0.414449,-0.916101 +102,1,0.593114,0.665157,5.54385,2.75346,0.414685,-0.916196 +103,1,0.593101,0.664345,5.54278,2.75378,0.415034,-0.915983 +104,1,0.593092,0.664573,5.54249,2.75364,0.414813,-0.91588 +105,1,0.593143,0.665006,5.54326,2.75335,0.41448,-0.916213 +106,1,0.593213,0.665049,5.54487,2.75252,0.413227,-0.91596 +107,1,0.593204,0.664769,5.54448,2.75378,0.41406,-0.916113 +108,1,0.593209,0.664582,5.54232,2.75314,0.414342,-0.915621 +109,1,0.593328,0.664871,5.54504,2.75302,0.41399,-0.916125 +110,1,0.593224,0.66473,5.54394,2.75338,0.414214,-0.915977 +111,1,0.593301,0.66439,5.54279,2.75386,0.414622,-0.915867 +112,1,0.593308,0.664861,5.54368,2.75247,0.413399,-0.915998 +113,1,0.593412,0.664681,5.54368,2.75317,0.41418,-0.915837 +114,1,0.592907,0.663442,5.54388,2.75347,0.414532,-0.915808 +115,1,0.593682,0.664435,5.54199,2.75315,0.414589,-0.915686 +116,1,0.59324,0.664844,5.5434,2.75388,0.415033,-0.915863 +117,1,0.593711,0.662009,5.54354,2.7537,0.413988,-0.915933 +118,1,0.593772,0.661943,5.54356,2.75355,0.413677,-0.915561 +119,1,0.5935,0.662749,5.54251,2.75485,0.415393,-0.91608 +120,1,0.593617,0.665351,5.54291,2.75341,0.414076,-0.916099 +121,1,0.593386,0.663832,5.54455,2.75259,0.413543,-0.915574 +122,1,0.593658,0.662736,5.5435,2.7537,0.413938,-0.915597 +123,1,0.593723,0.662353,5.54395,2.75325,0.414367,-0.915581 +124,1,0.593509,0.66287,5.54286,2.75306,0.41422,-0.915618 +125,1,0.5936,0.663384,5.54294,2.75381,0.414289,-0.915829 +126,1,0.59348,0.663534,5.54367,2.75299,0.413661,-0.915568 +127,1,0.593616,0.663914,5.5433,2.75335,0.413818,-0.915746 +128,1,0.593546,0.662732,5.5434,2.75397,0.414093,-0.915957 +129,1,0.593666,0.662417,5.54325,2.75394,0.414373,-0.915704 +130,1,0.593685,0.662892,5.54345,2.75436,0.414194,-0.916033 +131,1,0.593761,0.663742,5.54344,2.75318,0.413752,-0.915507 +132,1,0.593652,0.663448,5.54427,2.75396,0.414021,-0.915827 +133,1,0.593752,0.662601,5.5438,2.75342,0.414352,-0.915835 +134,1,0.593635,0.66265,5.54313,2.75331,0.414323,-0.915764 +135,1,0.593573,0.663018,5.54289,2.75349,0.414206,-0.915729 +136,1,0.593441,0.663383,5.54345,2.75347,0.413676,-0.915762 +137,1,0.593663,0.663061,5.54399,2.75332,0.414271,-0.916026 +138,1,0.59352,0.662863,5.54202,2.75347,0.414649,-0.915656 +139,1,0.593562,0.662523,5.54289,2.7537,0.414299,-0.915733 +140,1,0.593657,0.662683,5.54305,2.75423,0.414883,-0.915992 +141,1,0.593622,0.662979,5.54215,2.75399,0.414915,-0.915454 +142,1,0.593585,0.663226,5.54274,2.75379,0.414655,-0.915618 +143,1,0.59367,0.662719,5.54355,2.75389,0.414339,-0.916017 +144,1,0.593679,0.662491,5.54331,2.75357,0.414223,-0.915666 +145,1,0.593644,0.662878,5.543,2.75387,0.414333,-0.916129 +146,1,0.593442,0.662844,5.54163,2.75353,0.415133,-0.915478 +147,1,0.593741,0.663157,5.5439,2.7534,0.41374,-0.915823 +148,1,0.593611,0.662761,5.54253,2.75404,0.414982,-0.916063 +148,28,-3.24905,-12.141,36.7892,2.03219,-0.0332468,-1.33562 +149,1,0.5937,0.662991,5.54441,2.75345,0.41325,-0.915914 +150,1,0.593634,0.662797,5.54299,2.7541,0.414936,-0.916014 +151,1,0.593509,0.663003,5.54205,2.75399,0.415213,-0.915931 +152,1,0.593603,0.66301,5.54322,2.75281,0.413875,-0.91577 +153,1,0.593758,0.663022,5.54352,2.75361,0.414405,-0.915719 +154,1,0.593501,0.662814,5.54268,2.75357,0.414709,-0.915559 +155,1,0.59376,0.662766,5.54356,2.75369,0.414204,-0.915777 +156,1,0.59364,0.662786,5.54279,2.75401,0.414351,-0.916052 +157,1,0.593566,0.662856,5.54331,2.75394,0.414192,-0.915777 +158,1,0.593715,0.662877,5.54417,2.75343,0.414225,-0.915817 +159,1,0.59371,0.662794,5.54229,2.7545,0.415545,-0.915879 +160,1,0.593727,0.66272,5.54257,2.75358,0.415231,-0.91582 +161,1,0.593735,0.66283,5.54337,2.75372,0.414638,-0.916106 +162,1,0.593631,0.6628,5.54361,2.75355,0.414104,-0.916026 +163,1,0.593754,0.662752,5.54361,2.75375,0.414253,-0.915987 +164,1,0.59366,0.662912,5.54266,2.75423,0.415064,-0.915957 +165,1,0.593689,0.662858,5.54284,2.75377,0.414602,-0.916054 +166,1,0.59373,0.662733,5.54367,2.75296,0.414317,-0.915762 +167,1,0.593802,0.662706,5.54385,2.75396,0.414746,-0.915937 +168,1,0.593684,0.662709,5.5436,2.75327,0.414202,-0.915761 +169,1,0.593745,0.662915,5.54348,2.75375,0.414773,-0.915964 +170,1,0.593712,0.662576,5.54302,2.7537,0.414506,-0.915739 +171,1,0.593641,0.662623,5.54342,2.75325,0.414344,-0.915651 +172,1,0.593576,0.662739,5.54385,2.75373,0.414496,-0.91552 +173,1,0.5937,0.662807,5.54343,2.75365,0.414898,-0.916005 +174,1,0.593678,0.662755,5.54324,2.75387,0.414664,-0.915887 +175,1,0.593757,0.662629,5.54371,2.7532,0.414166,-0.915798 +176,1,0.593846,0.662721,5.54411,2.75402,0.414626,-0.916087 +177,1,0.59299,0.661245,5.53637,2.75326,0.414352,-0.915502 +178,1,0.592992,0.661411,5.53767,2.75236,0.41364,-0.915232 +179,1,0.593079,0.661528,5.53663,2.75379,0.414475,-0.915923 +180,1,0.59303,0.661414,5.53756,2.75398,0.414902,-0.915906 +181,1,0.59314,0.661383,5.53765,2.75287,0.414372,-0.915625 +182,1,0.593193,0.661614,5.53896,2.75316,0.413686,-0.91621 +183,1,0.593097,0.661354,5.53679,2.7538,0.415278,-0.916139 +184,1,0.593201,0.661708,5.53826,2.75411,0.415097,-0.915752 +185,1,0.593252,0.661596,5.53756,2.75449,0.415232,-0.915939 +186,1,0.59311,0.661543,5.53795,2.75301,0.414321,-0.915413 +187,1,0.593326,0.661558,5.53721,2.75438,0.415609,-0.916064 +188,1,0.593269,0.661763,5.53825,2.75394,0.414889,-0.915964 +189,1,0.593068,0.661699,5.53797,2.7541,0.415371,-0.915902 +190,1,0.593095,0.661455,5.53716,2.75408,0.41536,-0.915893 +191,1,0.593219,0.661574,5.53779,2.75373,0.414603,-0.91557 +192,1,0.593025,0.661259,5.53684,2.753,0.414107,-0.915374 +193,1,0.59322,0.661412,5.53721,2.75398,0.414849,-0.915662 +194,1,0.59312,0.661492,5.53718,2.7547,0.415355,-0.915896 +195,1,0.592973,0.661401,5.53689,2.75364,0.414873,-0.915683 +196,1,0.593229,0.661434,5.53815,2.7536,0.414104,-0.916018 +197,1,0.593054,0.661218,5.53756,2.75241,0.41344,-0.915434 +198,1,0.593123,0.661514,5.53806,2.75349,0.414646,-0.91588 +199,1,0.593274,0.661608,5.53747,2.75411,0.414354,-0.915849 +200,1,0.593023,0.661417,5.53696,2.7529,0.414121,-0.915584 +201,1,0.593205,0.661616,5.53793,2.75523,0.41479,-0.916215 +202,1,0.593139,0.661385,5.53793,2.75328,0.413482,-0.915864 +203,1,0.592938,0.661202,5.53656,2.75296,0.413539,-0.915678 +204,1,0.593092,0.66162,5.53754,2.75328,0.413562,-0.916127 +205,1,0.593021,0.661447,5.53625,2.75322,0.41435,-0.915978 +206,1,0.593157,0.661476,5.5382,2.75341,0.414073,-0.915688 +207,1,0.592837,0.661162,5.53614,2.75322,0.414537,-0.915915 +208,1,0.592956,0.661175,5.53657,2.75289,0.414291,-0.915655 +209,1,0.593045,0.661644,5.53759,2.75325,0.414285,-0.915341 +210,1,0.593157,0.661588,5.53769,2.75425,0.414205,-0.916008 +211,1,0.593115,0.661453,5.53725,2.75322,0.414425,-0.91538 +212,1,0.593142,0.661533,5.53836,2.75287,0.413591,-0.915716 +213,1,0.592982,0.66126,5.53707,2.75374,0.414223,-0.915811 +214,1,0.593105,0.661231,5.53616,2.7539,0.414468,-0.915749 +215,1,0.593021,0.661228,5.53617,2.75337,0.41437,-0.915499 +216,1,0.592876,0.66112,5.5363,2.7526,0.41389,-0.915304 +217,1,0.593146,0.661136,5.53819,2.75327,0.413573,-0.915797 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_april.txt new file mode 100644 index 0000000..74f9e47 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_april.txt @@ -0,0 +1,209 @@ +iter,id,x,y,z,r,p,y +0,1,8.33306,-0.915885,-1.24592,1.05384,0.540693,-0.129706 +1,1,8.33144,-0.91541,-1.24459,1.05427,0.540095,-0.129911 +2,1,8.33086,-0.91549,-1.24488,1.05442,0.540266,-0.129376 +3,1,8.33645,-0.916164,-1.24695,1.05444,0.539183,-0.130162 +4,1,8.33096,-0.915488,-1.24595,1.0537,0.541001,-0.128834 +5,1,8.33543,-0.915937,-1.24596,1.05405,0.539894,-0.129302 +6,1,8.33232,-0.915663,-1.24542,1.05429,0.540876,-0.12961 +7,1,8.33325,-0.9154,-1.24616,1.05447,0.540316,-0.130792 +8,1,8.33226,-0.915459,-1.24599,1.05377,0.539935,-0.128806 +9,1,8.33229,-0.915449,-1.24529,1.05424,0.540444,-0.129074 +10,1,8.33407,-0.91587,-1.24621,1.05464,0.540197,-0.129915 +11,1,8.33489,-0.915582,-1.24586,1.05426,0.539403,-0.130806 +12,1,8.33483,-0.915757,-1.24658,1.05472,0.539994,-0.130367 +13,1,8.33029,-0.915327,-1.24573,1.05431,0.540773,-0.129026 +14,1,8.33207,-0.915471,-1.24545,1.0536,0.539885,-0.129408 +15,1,8.33341,-0.915808,-1.24616,1.05436,0.539819,-0.129878 +16,1,8.33242,-0.915697,-1.24565,1.05356,0.540406,-0.129023 +17,1,8.33324,-0.91557,-1.24611,1.05372,0.539368,-0.128928 +18,1,8.33448,-0.915831,-1.24619,1.05436,0.539374,-0.129759 +19,1,8.332,-0.91527,-1.24531,1.0541,0.540522,-0.130475 +20,1,8.33305,-0.915686,-1.2458,1.05382,0.539809,-0.12811 +21,1,8.33169,-0.915438,-1.24613,1.05403,0.540293,-0.129842 +22,1,8.33126,-0.915307,-1.24569,1.05501,0.540786,-0.131863 +23,1,8.3307,-0.915514,-1.24537,1.0547,0.540561,-0.130729 +24,1,8.33474,-0.91625,-1.24622,1.05461,0.539427,-0.130457 +25,1,8.33435,-0.915499,-1.2463,1.05425,0.538989,-0.1294 +26,1,8.33557,-0.915974,-1.24612,1.05349,0.539294,-0.129195 +27,1,8.33336,-0.915635,-1.2461,1.05323,0.53992,-0.127334 +28,1,8.33268,-0.91566,-1.24575,1.05318,0.540011,-0.127922 +29,1,8.33281,-0.915602,-1.24615,1.05445,0.539968,-0.130114 +30,1,8.33487,-0.915782,-1.24637,1.05402,0.538622,-0.129616 +31,1,8.33127,-0.915481,-1.24526,1.05417,0.540569,-0.130193 +32,1,8.336,-0.916011,-1.2462,1.05492,0.539127,-0.130705 +33,1,8.33256,-0.91569,-1.24579,1.05432,0.540219,-0.130961 +34,1,8.33287,-0.915616,-1.24583,1.05459,0.540139,-0.130311 +35,1,8.33033,-0.915383,-1.24536,1.05502,0.540018,-0.131728 +36,1,8.33004,-0.915528,-1.24529,1.0542,0.540164,-0.129242 +37,1,8.33396,-0.915606,-1.24604,1.05423,0.539345,-0.130929 +38,1,8.33542,-0.915799,-1.24634,1.05449,0.539147,-0.131869 +39,1,8.3351,-0.915776,-1.24639,1.05409,0.539669,-0.129579 +40,1,8.33555,-0.915863,-1.24592,1.05479,0.539384,-0.132233 +41,1,8.33345,-0.915745,-1.24571,1.05466,0.539274,-0.131522 +42,1,8.33673,-0.91594,-1.24635,1.05468,0.538221,-0.131424 +43,1,8.33247,-0.915516,-1.24581,1.05414,0.539442,-0.128865 +44,1,8.33398,-0.915844,-1.24578,1.05415,0.539387,-0.130191 +45,1,8.33497,-0.916077,-1.24599,1.05554,0.538864,-0.131943 +46,1,8.33241,-0.915542,-1.2457,1.05466,0.539344,-0.131743 +47,1,8.33276,-0.915504,-1.24573,1.05464,0.539965,-0.131396 +48,1,8.33088,-0.915459,-1.24534,1.05411,0.540162,-0.130207 +49,1,8.33467,-0.915686,-1.24582,1.05478,0.53919,-0.131809 +50,1,8.33423,-0.915806,-1.24601,1.05397,0.539659,-0.129532 +51,1,8.3335,-0.915512,-1.2461,1.05465,0.540477,-0.131123 +52,1,8.33084,-0.915357,-1.2457,1.05385,0.540487,-0.129284 +53,1,8.33206,-0.915503,-1.24598,1.05414,0.540112,-0.128741 +54,1,8.33456,-0.915815,-1.24656,1.05464,0.539602,-0.131027 +55,1,8.33282,-0.915569,-1.24588,1.05388,0.539643,-0.129489 +56,1,8.33583,-0.915683,-1.24625,1.05456,0.539619,-0.132606 +57,1,8.33571,-0.915902,-1.24639,1.0545,0.539303,-0.13143 +58,1,8.33363,-0.915409,-1.24631,1.05399,0.539203,-0.129328 +59,1,8.33408,-0.915898,-1.24673,1.0542,0.539678,-0.130098 +60,1,8.337,-0.916038,-1.24712,1.05389,0.538714,-0.130435 +61,1,8.33157,-0.915515,-1.24623,1.05444,0.539364,-0.129336 +62,1,8.33281,-0.915526,-1.24668,1.05438,0.539814,-0.129318 +63,1,8.33716,-0.916061,-1.2473,1.05476,0.539786,-0.131559 +64,1,8.33511,-0.915995,-1.24669,1.05431,0.539134,-0.130601 +65,1,8.33507,-0.915499,-1.24666,1.05299,0.538966,-0.127772 +66,1,8.33601,-0.916081,-1.24669,1.05432,0.539351,-0.130653 +67,1,8.32977,-0.915177,-1.24599,1.05469,0.541009,-0.129728 +68,1,8.33186,-0.915317,-1.24586,1.05437,0.540193,-0.1304 +69,1,8.33179,-0.915282,-1.24601,1.05509,0.539578,-0.130842 +70,1,8.33358,-0.915564,-1.24608,1.05409,0.540091,-0.129317 +71,1,8.33716,-0.915626,-1.24711,1.05451,0.538862,-0.131272 +72,1,8.33427,-0.915542,-1.24666,1.05487,0.539649,-0.131594 +73,1,8.33176,-0.915288,-1.24551,1.05388,0.540153,-0.128649 +74,1,8.33205,-0.915376,-1.24577,1.05417,0.539005,-0.129872 +75,1,8.33215,-0.915444,-1.24661,1.05406,0.53905,-0.129717 +76,1,8.32973,-0.915161,-1.24582,1.05411,0.540538,-0.12879 +77,1,8.33159,-0.915157,-1.24588,1.05439,0.539773,-0.130962 +78,1,8.33408,-0.915476,-1.24642,1.05382,0.539829,-0.129963 +79,1,8.3298,-0.915058,-1.2464,1.05397,0.539859,-0.12971 +80,1,8.33364,-0.915462,-1.24676,1.05333,0.539575,-0.129009 +81,1,8.33122,-0.915127,-1.24639,1.05399,0.539993,-0.128686 +82,1,8.3337,-0.915515,-1.24645,1.05368,0.539024,-0.128587 +83,1,8.33209,-0.915159,-1.24678,1.05443,0.539597,-0.129779 +84,1,8.33173,-0.915396,-1.24663,1.05452,0.539974,-0.129124 +85,1,8.33099,-0.91518,-1.24668,1.0541,0.53995,-0.129612 +86,1,8.33434,-0.915646,-1.24662,1.05378,0.539216,-0.130588 +87,1,8.33339,-0.915636,-1.24647,1.05391,0.539209,-0.128991 +88,1,8.33492,-0.915639,-1.24691,1.05436,0.538712,-0.129967 +89,1,8.33163,-0.915369,-1.24618,1.05368,0.539346,-0.127499 +90,1,8.33485,-0.915796,-1.24698,1.05416,0.539643,-0.128648 +91,1,8.33197,-0.91536,-1.24638,1.05397,0.539798,-0.128373 +92,1,8.33313,-0.915457,-1.24679,1.05385,0.539791,-0.12915 +93,1,8.33426,-0.915678,-1.24676,1.05397,0.539788,-0.129098 +94,1,8.33063,-0.915247,-1.24601,1.054,0.540401,-0.129056 +95,1,8.33398,-0.915408,-1.24631,1.05485,0.539843,-0.131259 +96,1,8.33163,-0.915376,-1.24602,1.05489,0.541049,-0.131262 +97,1,8.3307,-0.915092,-1.24596,1.05466,0.540742,-0.129687 +98,1,8.33184,-0.915119,-1.24627,1.05405,0.539963,-0.128947 +99,1,8.3353,-0.915646,-1.2471,1.05484,0.539297,-0.130104 +100,1,8.33201,-0.915064,-1.24672,1.05441,0.539829,-0.129888 +101,1,8.33355,-0.915492,-1.2467,1.05478,0.539722,-0.130615 +102,1,8.3307,-0.915195,-1.24644,1.05385,0.540248,-0.127926 +103,1,8.33173,-0.915442,-1.24681,1.055,0.540866,-0.130028 +104,1,8.33765,-0.915832,-1.24721,1.05463,0.538628,-0.130312 +105,1,8.33449,-0.915821,-1.2471,1.05383,0.539107,-0.12874 +106,1,8.3307,-0.915146,-1.24635,1.05469,0.539904,-0.130131 +107,1,8.33232,-0.915433,-1.24641,1.05465,0.540087,-0.130224 +108,1,8.33264,-0.915548,-1.24644,1.05443,0.539657,-0.129521 +109,1,8.33436,-0.91562,-1.24638,1.05365,0.539495,-0.128772 +110,1,8.3358,-0.915763,-1.24707,1.05392,0.539333,-0.129207 +111,1,8.33442,-0.915801,-1.24694,1.05351,0.539585,-0.127449 +112,1,8.33212,-0.915273,-1.24656,1.0544,0.539978,-0.129377 +113,1,8.3349,-0.915724,-1.24645,1.05421,0.539715,-0.130129 +114,1,8.33385,-0.915421,-1.2467,1.05364,0.539513,-0.128572 +115,1,8.33259,-0.915464,-1.24704,1.05413,0.539832,-0.128739 +116,1,8.33275,-0.915351,-1.24698,1.05469,0.539473,-0.12934 +117,1,8.3344,-0.915472,-1.2466,1.0542,0.539565,-0.130307 +118,1,8.33177,-0.915291,-1.24623,1.05376,0.539322,-0.129656 +119,1,8.33266,-0.915273,-1.24706,1.05428,0.539969,-0.130012 +120,1,8.33394,-0.915771,-1.24686,1.05431,0.539759,-0.129726 +121,1,8.3328,-0.915336,-1.24624,1.05381,0.539763,-0.129401 +122,1,8.33279,-0.915426,-1.24662,1.05441,0.539218,-0.130414 +123,1,8.33475,-0.915702,-1.24727,1.05419,0.539437,-0.1303 +124,1,8.33567,-0.915901,-1.24712,1.05405,0.539288,-0.128953 +125,1,8.33244,-0.915326,-1.24605,1.05448,0.540017,-0.129831 +126,1,8.3356,-0.915694,-1.2472,1.05428,0.539486,-0.130705 +127,1,8.33352,-0.915365,-1.24722,1.05438,0.538898,-0.12949 +128,1,8.33777,-0.91575,-1.24752,1.05383,0.538444,-0.129074 +129,1,8.33324,-0.915452,-1.24659,1.05346,0.539149,-0.129721 +130,1,8.33564,-0.915672,-1.24685,1.05386,0.539056,-0.129992 +131,1,8.33319,-0.915298,-1.24687,1.05394,0.539733,-0.130067 +132,1,8.33266,-0.915376,-1.24708,1.05432,0.539168,-0.130584 +133,1,8.33067,-0.914945,-1.2464,1.05492,0.540644,-0.130835 +134,1,8.33207,-0.915225,-1.24636,1.0546,0.539726,-0.130681 +135,1,8.33248,-0.915346,-1.24652,1.05433,0.539033,-0.129508 +136,1,8.33092,-0.915105,-1.2466,1.05458,0.540022,-0.129088 +137,1,8.32969,-0.915181,-1.24619,1.0541,0.539818,-0.128624 +138,1,8.33253,-0.915337,-1.2465,1.05361,0.538919,-0.128814 +139,1,8.32803,-0.914931,-1.2456,1.05409,0.540362,-0.128361 +140,1,8.33278,-0.915385,-1.24685,1.05463,0.538831,-0.13099 +141,1,8.3328,-0.915306,-1.24692,1.05424,0.538668,-0.130319 +142,1,8.33476,-0.915624,-1.24658,1.05449,0.539274,-0.130719 +143,1,8.33431,-0.915511,-1.24651,1.05405,0.539212,-0.129864 +144,1,8.33211,-0.915432,-1.24665,1.05403,0.539808,-0.128767 +145,1,8.33278,-0.915146,-1.24688,1.05456,0.539239,-0.131027 +146,1,8.33129,-0.915005,-1.24617,1.05356,0.539436,-0.128732 +147,1,8.33411,-0.915634,-1.24657,1.05453,0.539192,-0.130736 +148,1,8.33134,-0.915222,-1.24638,1.05399,0.540365,-0.129852 +149,1,8.33351,-0.915156,-1.24674,1.0546,0.539881,-0.131428 +150,1,8.33047,-0.915282,-1.2465,1.05388,0.540345,-0.129433 +151,1,8.33269,-0.9153,-1.24638,1.05444,0.539556,-0.129603 +152,1,8.33338,-0.915254,-1.24656,1.0543,0.53947,-0.129735 +153,1,8.33326,-0.915496,-1.24703,1.05321,0.539303,-0.128029 +154,1,8.33275,-0.915417,-1.24643,1.05431,0.539861,-0.129738 +155,1,8.33322,-0.91533,-1.24622,1.0538,0.540261,-0.129258 +156,1,8.3336,-0.915496,-1.24668,1.05451,0.539664,-0.130168 +157,1,8.3342,-0.915448,-1.24668,1.05369,0.540302,-0.130077 +158,1,8.33395,-0.915182,-1.24647,1.05453,0.539472,-0.131061 +159,1,8.3308,-0.914998,-1.24636,1.05412,0.540715,-0.129684 +160,1,8.33072,-0.914847,-1.24645,1.0538,0.540499,-0.129211 +161,1,8.33397,-0.915378,-1.24684,1.05442,0.539564,-0.130403 +162,1,8.33156,-0.915176,-1.24643,1.05422,0.540246,-0.130099 +163,1,8.33076,-0.914963,-1.24637,1.05339,0.540462,-0.12783 +164,1,8.33662,-0.915848,-1.24718,1.05486,0.539249,-0.130595 +165,1,8.33579,-0.915695,-1.24722,1.05493,0.53909,-0.130912 +166,1,8.3315,-0.915227,-1.2463,1.0538,0.540343,-0.128945 +167,1,8.33118,-0.915179,-1.24661,1.05499,0.540033,-0.130362 +168,1,8.33258,-0.915312,-1.24703,1.05431,0.539344,-0.129823 +169,1,8.33361,-0.915474,-1.24722,1.05425,0.539746,-0.129748 +170,1,8.33464,-0.915493,-1.24726,1.05399,0.539127,-0.129365 +171,1,8.331,-0.915158,-1.24684,1.05342,0.53988,-0.127024 +172,1,8.32847,-0.914905,-1.24627,1.05376,0.539687,-0.12766 +173,1,8.33086,-0.914867,-1.24686,1.05484,0.539518,-0.131286 +174,1,8.33528,-0.915534,-1.24747,1.05392,0.538706,-0.130198 +175,1,8.33394,-0.915225,-1.24721,1.05414,0.539325,-0.129485 +176,1,8.33452,-0.915193,-1.24706,1.05499,0.539104,-0.130273 +177,1,8.33118,-0.9152,-1.24687,1.05413,0.539156,-0.130666 +178,1,8.32956,-0.915053,-1.2465,1.05473,0.540206,-0.13093 +179,1,8.32932,-0.914967,-1.24633,1.05426,0.540648,-0.128856 +180,1,8.33359,-0.915479,-1.2471,1.05396,0.539699,-0.129361 +181,1,8.33386,-0.915312,-1.24741,1.05426,0.539089,-0.12973 +182,1,8.33279,-0.915295,-1.2472,1.05437,0.539275,-0.129891 +183,1,8.33144,-0.915323,-1.24677,1.05446,0.539699,-0.12947 +184,1,8.33297,-0.915465,-1.24706,1.05453,0.539777,-0.130823 +185,1,8.33339,-0.91515,-1.24691,1.05359,0.538922,-0.129937 +186,1,8.33613,-0.915465,-1.24761,1.05385,0.538703,-0.130193 +187,1,8.33221,-0.914995,-1.24684,1.05413,0.539652,-0.130446 +188,1,8.33128,-0.914889,-1.24602,1.05424,0.540616,-0.12986 +189,1,8.33545,-0.915341,-1.24676,1.05396,0.538976,-0.130437 +190,1,8.3318,-0.915179,-1.24673,1.05422,0.53949,-0.128821 +191,1,8.33351,-0.915438,-1.24682,1.05397,0.539337,-0.128693 +192,1,8.33174,-0.915087,-1.24659,1.05416,0.540037,-0.128649 +193,1,8.33102,-0.915045,-1.24619,1.05512,0.53986,-0.130073 +194,1,8.33269,-0.915301,-1.2466,1.05464,0.539211,-0.130448 +195,1,8.33136,-0.915153,-1.24613,1.05429,0.540326,-0.130422 +196,1,8.32971,-0.914923,-1.24601,1.05484,0.541099,-0.130483 +197,1,8.3329,-0.915389,-1.24639,1.0541,0.540377,-0.129256 +198,1,8.33311,-0.915484,-1.24634,1.05359,0.539819,-0.129867 +199,1,8.33095,-0.914933,-1.24614,1.05408,0.540223,-0.130216 +200,1,8.33287,-0.91516,-1.24677,1.05462,0.539519,-0.132094 +201,1,8.33215,-0.915243,-1.24662,1.05439,0.539712,-0.129405 +202,1,8.332,-0.91532,-1.2466,1.05428,0.53983,-0.129728 +203,1,8.33261,-0.91536,-1.24685,1.05407,0.539376,-0.129164 +204,1,8.33191,-0.91516,-1.24693,1.05374,0.539443,-0.128899 +205,1,8.33237,-0.915235,-1.24714,1.05469,0.539219,-0.131452 +206,1,8.33258,-0.915175,-1.24684,1.05418,0.540093,-0.129662 +207,1,8.33364,-0.915353,-1.24683,1.05383,0.539191,-0.13017 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_other.txt new file mode 100644 index 0000000..c12c9b5 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-3/pose_other.txt @@ -0,0 +1,209 @@ +iter,id,x,y,z,r,p,y +0,1,0.919668,1.2527,8.42195,2.74679,0.384299,-0.939077 +1,1,0.919272,1.25148,8.42097,2.74727,0.383727,-0.939735 +2,1,0.919318,1.25171,8.42011,2.74762,0.384293,-0.939952 +3,1,0.919978,1.25378,8.42566,2.74762,0.382976,-0.94009 +4,1,0.919266,1.25272,8.41978,2.74737,0.385051,-0.939139 +5,1,0.919796,1.25284,8.42497,2.74787,0.383862,-0.939799 +6,1,0.919472,1.25223,8.42139,2.74701,0.384667,-0.939535 +7,1,0.919251,1.25304,8.42276,2.7464,0.383466,-0.939547 +8,1,0.919281,1.25283,8.4215,2.74808,0.384111,-0.939616 +9,1,0.919251,1.2521,8.4213,2.74775,0.384629,-0.939822 +10,1,0.919687,1.25303,8.42324,2.74731,0.384048,-0.940025 +11,1,0.919414,1.25271,8.42422,2.74689,0.382671,-0.93965 +12,1,0.919552,1.25338,8.42384,2.74705,0.383677,-0.940009 +13,1,0.919145,1.25255,8.41944,2.74761,0.384917,-0.939796 +14,1,0.919298,1.25229,8.42134,2.74754,0.383642,-0.939277 +15,1,0.919655,1.25302,8.42285,2.7475,0.383587,-0.939916 +16,1,0.919495,1.25246,8.42137,2.74763,0.384402,-0.939194 +17,1,0.91944,1.25301,8.42288,2.74841,0.383489,-0.939783 +18,1,0.919651,1.25303,8.42371,2.74785,0.383337,-0.940094 +19,1,0.919051,1.25209,8.42082,2.74643,0.383851,-0.939186 +20,1,0.91954,1.25267,8.42255,2.74883,0.384391,-0.939965 +21,1,0.91932,1.25304,8.42149,2.74703,0.383743,-0.939422 +22,1,0.919103,1.2525,8.42024,2.74537,0.38356,-0.939531 +23,1,0.919365,1.25224,8.42019,2.74632,0.38377,-0.939676 +24,1,0.920075,1.25306,8.42399,2.7473,0.383065,-0.940099 +25,1,0.9193,1.25311,8.42342,2.74838,0.383234,-0.940244 +26,1,0.919792,1.25295,8.42478,2.74803,0.383258,-0.939432 +27,1,0.919451,1.25292,8.4225,2.74927,0.384823,-0.939599 +28,1,0.919464,1.25256,8.42174,2.74857,0.384508,-0.939281 +29,1,0.919396,1.25295,8.42181,2.74715,0.383687,-0.939825 +30,1,0.91962,1.25323,8.42423,2.74841,0.382671,-0.940118 +31,1,0.919294,1.25208,8.42038,2.74666,0.384009,-0.93934 +32,1,0.919839,1.25305,8.42527,2.74747,0.382814,-0.940458 +33,1,0.919519,1.25264,8.42189,2.74615,0.383236,-0.939322 +34,1,0.919423,1.25264,8.42197,2.74694,0.383746,-0.939852 +35,1,0.919204,1.25219,8.41957,2.7459,0.38292,-0.939845 +36,1,0.919383,1.25217,8.41951,2.74781,0.384183,-0.939868 +37,1,0.919441,1.2529,8.42333,2.74677,0.382517,-0.939589 +38,1,0.9196,1.25315,8.42449,2.74622,0.382,-0.939612 +39,1,0.91956,1.25317,8.42401,2.7477,0.383653,-0.939756 +40,1,0.919671,1.25273,8.42467,2.74584,0.382073,-0.939697 +41,1,0.919563,1.25254,8.42265,2.74647,0.382326,-0.939842 +42,1,0.919746,1.25317,8.42582,2.74735,0.381607,-0.940312 +43,1,0.919377,1.25269,8.42201,2.7486,0.383785,-0.940202 +44,1,0.919615,1.25255,8.42278,2.74732,0.383092,-0.939693 +45,1,0.919877,1.25279,8.424,2.74675,0.382159,-0.940738 +46,1,0.919366,1.25254,8.4217,2.74618,0.38221,-0.939733 +47,1,0.919332,1.25258,8.42206,2.74614,0.382932,-0.939621 +48,1,0.919239,1.25212,8.41971,2.74685,0.383704,-0.939397 +49,1,0.919509,1.25266,8.42391,2.74638,0.382149,-0.939929 +50,1,0.919629,1.25284,8.42347,2.74772,0.383547,-0.939681 +51,1,0.919331,1.25293,8.42274,2.74598,0.383503,-0.939502 +52,1,0.919196,1.25255,8.42021,2.74736,0.384277,-0.939347 +53,1,0.919305,1.25279,8.42105,2.74829,0.384549,-0.939976 +54,1,0.919713,1.2535,8.42451,2.7467,0.382699,-0.939904 +55,1,0.919361,1.25268,8.42176,2.74779,0.383616,-0.939622 +56,1,0.919495,1.25308,8.42498,2.74533,0.381961,-0.939284 +57,1,0.919731,1.25323,8.42503,2.7465,0.382327,-0.93972 +58,1,0.91923,1.25315,8.42282,2.74835,0.383369,-0.939989 +59,1,0.919742,1.2536,8.42356,2.74723,0.383235,-0.939695 +60,1,0.91991,1.25403,8.42671,2.74756,0.382117,-0.939688 +61,1,0.919367,1.25311,8.42111,2.74821,0.383509,-0.940311 +62,1,0.919387,1.25357,8.4224,2.74801,0.38389,-0.940135 +63,1,0.919889,1.25415,8.42652,2.74611,0.382721,-0.939728 +64,1,0.919851,1.25357,8.4247,2.74722,0.382525,-0.939858 +65,1,0.919355,1.25355,8.42461,2.7494,0.383586,-0.939579 +66,1,0.919886,1.25351,8.42509,2.74711,0.38283,-0.939777 +67,1,0.918972,1.25279,8.41875,2.74699,0.384886,-0.939838 +68,1,0.919185,1.25276,8.42152,2.74676,0.383507,-0.939615 +69,1,0.919132,1.25289,8.42126,2.74713,0.383111,-0.940434 +70,1,0.919389,1.25292,8.42284,2.74768,0.384065,-0.939713 +71,1,0.91948,1.254,8.42676,2.74689,0.381983,-0.939941 +72,1,0.919371,1.25352,8.42361,2.74628,0.382653,-0.939913 +73,1,0.919092,1.25232,8.42083,2.74811,0.384464,-0.93969 +74,1,0.919188,1.2526,8.42118,2.74797,0.382931,-0.940023 +75,1,0.919257,1.25344,8.42134,2.74798,0.382984,-0.939923 +76,1,0.918972,1.25264,8.41885,2.74785,0.384773,-0.939735 +77,1,0.918976,1.25271,8.42082,2.74655,0.382948,-0.939583 +78,1,0.91929,1.25325,8.42326,2.74717,0.38338,-0.939325 +79,1,0.918882,1.25324,8.41907,2.74745,0.383592,-0.939558 +80,1,0.91924,1.25354,8.42252,2.74796,0.383615,-0.939215 +81,1,0.918996,1.25329,8.4209,2.74826,0.384211,-0.939878 +82,1,0.919349,1.2533,8.42309,2.74879,0.383415,-0.939917 +83,1,0.919072,1.25375,8.42219,2.74772,0.383312,-0.940127 +84,1,0.919233,1.25349,8.4211,2.7481,0.384236,-0.94026 +85,1,0.919021,1.25354,8.42046,2.74744,0.383698,-0.939657 +86,1,0.91947,1.25346,8.42363,2.74702,0.382475,-0.939307 +87,1,0.919423,1.25326,8.4223,2.74851,0.383579,-0.939963 +88,1,0.919445,1.25373,8.42406,2.7481,0.382699,-0.940258 +89,1,0.919213,1.25305,8.42109,2.74955,0.384307,-0.940169 +90,1,0.919597,1.25379,8.4239,2.7486,0.384192,-0.940161 +91,1,0.919171,1.2532,8.42114,2.74858,0.384339,-0.939982 +92,1,0.919243,1.25359,8.42207,2.7479,0.3839,-0.939616 +93,1,0.919495,1.2536,8.42349,2.74797,0.383898,-0.939758 +94,1,0.919043,1.25282,8.41963,2.74766,0.384492,-0.939585 +95,1,0.919206,1.25312,8.42301,2.74646,0.383085,-0.939927 +96,1,0.919148,1.25279,8.42044,2.7456,0.384097,-0.939472 +97,1,0.91889,1.25277,8.41973,2.74708,0.384629,-0.939888 +98,1,0.918986,1.25317,8.42148,2.74811,0.384079,-0.939878 +99,1,0.919543,1.25404,8.42529,2.74771,0.383043,-0.940494 +100,1,0.918916,1.2536,8.42155,2.74747,0.383567,-0.939954 +101,1,0.919367,1.25361,8.42332,2.74698,0.383119,-0.940108 +102,1,0.919004,1.25326,8.41982,2.74869,0.384951,-0.939865 +103,1,0.919288,1.25368,8.42123,2.74682,0.384549,-0.940081 +104,1,0.919699,1.25412,8.42733,2.74797,0.382403,-0.940478 +105,1,0.919676,1.25398,8.42402,2.74881,0.383478,-0.94005 +106,1,0.918979,1.25321,8.42002,2.74739,0.383677,-0.940145 +107,1,0.919272,1.25327,8.42176,2.747,0.383665,-0.939944 +108,1,0.919394,1.25331,8.42209,2.74794,0.383692,-0.940167 +109,1,0.919502,1.2533,8.42416,2.74836,0.383593,-0.939694 +110,1,0.919681,1.25404,8.42592,2.74824,0.383256,-0.93992 +111,1,0.91961,1.25376,8.42356,2.74942,0.384572,-0.939929 +112,1,0.919102,1.25342,8.42141,2.74788,0.384073,-0.940067 +113,1,0.919561,1.25331,8.42427,2.7473,0.383318,-0.939728 +114,1,0.919239,1.25353,8.42307,2.74853,0.383871,-0.93972 +115,1,0.919301,1.2539,8.42199,2.74834,0.384169,-0.940031 +116,1,0.919212,1.25387,8.42241,2.7482,0.383657,-0.940511 +117,1,0.919324,1.25348,8.42396,2.74714,0.383001,-0.939681 +118,1,0.919112,1.25308,8.42098,2.74784,0.383146,-0.939586 +119,1,0.919132,1.25395,8.42233,2.74708,0.383474,-0.93968 +120,1,0.919628,1.25374,8.42355,2.74752,0.383521,-0.939892 +121,1,0.919186,1.25312,8.4223,2.74773,0.383583,-0.939548 +122,1,0.91932,1.25356,8.4227,2.74745,0.382686,-0.940042 +123,1,0.919574,1.25418,8.42448,2.74727,0.382873,-0.939741 +124,1,0.91977,1.25402,8.42538,2.74847,0.383497,-0.940093 +125,1,0.91911,1.25283,8.42131,2.74748,0.383974,-0.939967 +126,1,0.919529,1.25406,8.42503,2.74687,0.382769,-0.939647 +127,1,0.919217,1.25411,8.42311,2.74834,0.383002,-0.940367 +128,1,0.919626,1.25444,8.42756,2.74884,0.382638,-0.940154 +129,1,0.919299,1.25347,8.42274,2.74766,0.382736,-0.939295 +130,1,0.919552,1.25377,8.42547,2.7476,0.382567,-0.939641 +131,1,0.919155,1.25376,8.42278,2.74718,0.383182,-0.939461 +132,1,0.919218,1.25395,8.42215,2.74719,0.382573,-0.939849 +133,1,0.918844,1.25335,8.4206,2.74639,0.383801,-0.939903 +134,1,0.91907,1.25323,8.42154,2.7469,0.3831,-0.939911 +135,1,0.919204,1.25341,8.42207,2.74829,0.383101,-0.940291 +136,1,0.918988,1.25352,8.42075,2.74804,0.384169,-0.940306 +137,1,0.918993,1.25302,8.41884,2.74848,0.384291,-0.94006 +138,1,0.919229,1.25343,8.42244,2.74865,0.383041,-0.939849 +139,1,0.918728,1.2524,8.41701,2.74836,0.384923,-0.939932 +140,1,0.919256,1.25376,8.42252,2.7472,0.382128,-0.940166 +141,1,0.919183,1.25384,8.42259,2.74775,0.382227,-0.94007 +142,1,0.919445,1.25341,8.42405,2.74705,0.382694,-0.939918 +143,1,0.919392,1.25343,8.4241,2.74777,0.382885,-0.939849 +144,1,0.919236,1.25347,8.42118,2.74834,0.384194,-0.939937 +145,1,0.91898,1.25375,8.42214,2.747,0.382551,-0.939973 +146,1,0.918876,1.25307,8.421,2.74838,0.383536,-0.93963 +147,1,0.919511,1.25349,8.42386,2.74722,0.382557,-0.940048 +148,1,0.919084,1.25327,8.42098,2.74694,0.383816,-0.93934 +149,1,0.919001,1.25362,8.423,2.74615,0.382781,-0.939609 +150,1,0.919114,1.25335,8.41982,2.74731,0.384087,-0.939369 +151,1,0.919133,1.25323,8.42204,2.74791,0.383575,-0.940166 +152,1,0.919118,1.25346,8.42302,2.7478,0.383299,-0.940033 +153,1,0.919312,1.25387,8.42248,2.74896,0.383848,-0.939541 +154,1,0.919278,1.25332,8.42234,2.74758,0.383647,-0.939912 +155,1,0.919197,1.25312,8.42287,2.74751,0.384025,-0.939404 +156,1,0.91937,1.2536,8.42333,2.7474,0.383278,-0.940046 +157,1,0.919364,1.25364,8.4243,2.74675,0.38343,-0.939045 +158,1,0.919003,1.25331,8.42322,2.74671,0.382692,-0.939803 +159,1,0.918842,1.25323,8.42024,2.74696,0.384312,-0.939402 +160,1,0.918673,1.25329,8.42004,2.74732,0.384295,-0.939286 +161,1,0.919259,1.25376,8.42377,2.7472,0.382993,-0.939908 +162,1,0.919041,1.25333,8.42118,2.74698,0.383698,-0.939564 +163,1,0.918788,1.25321,8.42003,2.74848,0.384967,-0.939382 +164,1,0.919682,1.25404,8.426,2.74742,0.38292,-0.940384 +165,1,0.919557,1.25412,8.42544,2.74726,0.382551,-0.94041 +166,1,0.91909,1.2532,8.42105,2.74787,0.384353,-0.939529 +167,1,0.919018,1.25347,8.4206,2.74714,0.383712,-0.940292 +168,1,0.919138,1.25388,8.4219,2.74779,0.383226,-0.940039 +169,1,0.919305,1.25407,8.42299,2.74753,0.383548,-0.93984 +170,1,0.919349,1.25415,8.42426,2.74817,0.383108,-0.939942 +171,1,0.918988,1.25369,8.42031,2.74959,0.384987,-0.939897 +172,1,0.91876,1.25315,8.41803,2.74922,0.384487,-0.940076 +173,1,0.918702,1.25373,8.4203,2.74656,0.38266,-0.94001 +174,1,0.919398,1.25438,8.425,2.74766,0.382212,-0.939748 +175,1,0.919088,1.25412,8.42358,2.74806,0.383274,-0.940018 +176,1,0.919035,1.25394,8.424,2.74781,0.382996,-0.940665 +177,1,0.919114,1.25384,8.4213,2.74713,0.382306,-0.939698 +178,1,0.918898,1.25337,8.41903,2.74642,0.383389,-0.939784 +179,1,0.918742,1.2531,8.41816,2.74774,0.384941,-0.939792 +180,1,0.919316,1.25396,8.42301,2.74781,0.383622,-0.939709 +181,1,0.919143,1.25426,8.42326,2.74794,0.383009,-0.940083 +182,1,0.919087,1.254,8.42183,2.74776,0.383211,-0.940067 +183,1,0.919191,1.25367,8.42112,2.74793,0.383693,-0.940191 +184,1,0.919317,1.25394,8.42254,2.74667,0.382994,-0.939761 +185,1,0.91903,1.25383,8.42323,2.74765,0.38238,-0.939444 +186,1,0.919247,1.25441,8.4251,2.74769,0.38239,-0.939662 +187,1,0.918795,1.25366,8.42131,2.74698,0.383091,-0.939534 +188,1,0.918732,1.25289,8.4207,2.74694,0.38419,-0.939516 +189,1,0.919206,1.25366,8.42512,2.74739,0.382347,-0.939651 +190,1,0.919069,1.25366,8.42168,2.74853,0.383757,-0.940251 +191,1,0.91929,1.2537,8.42305,2.74867,0.383711,-0.940094 +192,1,0.918901,1.25342,8.42092,2.74834,0.384468,-0.940026 +193,1,0.918899,1.25308,8.42054,2.74758,0.383773,-0.940601 +194,1,0.919153,1.25349,8.42223,2.74749,0.382836,-0.940239 +195,1,0.918954,1.25294,8.42041,2.74665,0.383734,-0.939458 +196,1,0.918699,1.25279,8.41852,2.74631,0.384605,-0.939698 +197,1,0.919151,1.25314,8.42161,2.74752,0.384466,-0.939601 +198,1,0.919371,1.25326,8.42294,2.74719,0.383178,-0.939165 +199,1,0.918765,1.25299,8.42029,2.74679,0.383605,-0.939367 +200,1,0.919004,1.25364,8.42238,2.74578,0.382085,-0.939531 +201,1,0.919105,1.25351,8.4218,2.7479,0.383706,-0.940117 +202,1,0.9192,1.25352,8.42181,2.74749,0.383522,-0.939868 +203,1,0.91922,1.25374,8.42221,2.74828,0.383485,-0.940029 +204,1,0.91894,1.25371,8.42081,2.74831,0.383733,-0.939716 +205,1,0.919147,1.2541,8.42252,2.74651,0.382072,-0.939934 +206,1,0.918999,1.25369,8.42183,2.74749,0.38393,-0.939725 +207,1,0.919199,1.25371,8.42315,2.74738,0.382648,-0.939499 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-4/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-4/pose_april.txt new file mode 100644 index 0000000..887c1d1 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-4/pose_april.txt @@ -0,0 +1,212 @@ +iter,id,x,y,z,r,p,y +0,1,11.0629,-0.980896,-1.23842,1.02506,0.527355,-0.0765492 +1,1,11.0612,-0.980322,-1.24053,1.02483,0.528303,-0.0756247 +2,1,11.0664,-0.980848,-1.23928,1.02646,0.527855,-0.0785065 +3,1,11.0709,-0.981322,-1.23767,1.02511,0.525778,-0.0752154 +4,1,11.0592,-0.980176,-1.23655,1.02474,0.528778,-0.0759494 +5,1,11.0617,-0.980566,-1.23862,1.02518,0.528131,-0.0760832 +6,1,11.0621,-0.980559,-1.24135,1.02574,0.52914,-0.0776336 +7,1,11.0679,-0.980955,-1.24132,1.02506,0.527605,-0.0777481 +8,1,11.0608,-0.979893,-1.23925,1.02517,0.528478,-0.0760383 +9,1,11.0703,-0.980848,-1.23905,1.02545,0.526204,-0.0785887 +10,1,11.0604,-0.980143,-1.23819,1.02538,0.52826,-0.0751949 +11,1,11.0695,-0.980789,-1.24075,1.02498,0.527245,-0.0764047 +12,1,11.0727,-0.981011,-1.24129,1.02552,0.527174,-0.0783591 +13,1,11.0623,-0.980102,-1.23977,1.02373,0.52758,-0.0728945 +14,1,11.0685,-0.980902,-1.23887,1.02468,0.527169,-0.0760429 +15,1,11.0676,-0.980773,-1.23879,1.02563,0.527144,-0.0764305 +16,1,11.0619,-0.980434,-1.23917,1.02536,0.528213,-0.0772601 +17,1,11.0683,-0.980925,-1.24053,1.02561,0.526862,-0.0786216 +18,1,11.0659,-0.980887,-1.23996,1.02486,0.527122,-0.0771067 +19,1,11.0623,-0.980525,-1.23864,1.02555,0.528393,-0.0757575 +20,1,11.0685,-0.980426,-1.23851,1.02541,0.527298,-0.0764763 +21,1,11.0613,-0.980464,-1.2388,1.02525,0.527571,-0.0768814 +22,1,11.0642,-0.980598,-1.24022,1.02451,0.527931,-0.0747104 +23,1,11.0611,-0.980187,-1.24017,1.0252,0.528569,-0.0758808 +24,1,11.0733,-0.981065,-1.24038,1.02525,0.526303,-0.0776562 +25,1,11.0661,-0.980317,-1.23858,1.0253,0.526066,-0.0762287 +26,1,11.0704,-0.980866,-1.23851,1.02518,0.527004,-0.0785829 +27,1,11.0682,-0.980559,-1.23968,1.02376,0.526716,-0.0741505 +28,1,11.0644,-0.980507,-1.23999,1.02598,0.527974,-0.0769111 +29,1,11.0679,-0.980751,-1.23934,1.0249,0.527367,-0.0774102 +30,1,11.0607,-0.980388,-1.23905,1.02571,0.528168,-0.0770233 +31,1,11.0696,-0.981084,-1.24161,1.02444,0.526411,-0.0744622 +32,1,11.0675,-0.980948,-1.23995,1.02563,0.527425,-0.0777905 +33,1,11.067,-0.980593,-1.24014,1.02526,0.527267,-0.0773837 +34,1,11.0675,-0.980654,-1.23881,1.02574,0.526793,-0.0788072 +35,1,11.0662,-0.98034,-1.23854,1.02482,0.526768,-0.0781948 +36,1,11.0668,-0.980662,-1.2405,1.02492,0.527427,-0.0753469 +37,1,11.0619,-0.979872,-1.2393,1.02437,0.528649,-0.0753906 +38,1,11.0645,-0.979913,-1.23963,1.02576,0.527842,-0.0775695 +39,1,11.0663,-0.980273,-1.23889,1.02492,0.527087,-0.0785243 +40,1,11.0683,-0.980517,-1.23951,1.02558,0.527091,-0.079522 +41,1,11.0645,-0.980219,-1.23907,1.02503,0.527175,-0.0773906 +42,1,11.0702,-0.980574,-1.23901,1.02503,0.526408,-0.0776634 +43,1,11.0661,-0.980199,-1.23906,1.02596,0.528103,-0.0793604 +44,1,11.0663,-0.97994,-1.23868,1.02413,0.527189,-0.0756316 +45,1,11.0616,-0.979561,-1.23886,1.02472,0.528204,-0.0755224 +46,1,11.068,-0.980266,-1.23988,1.02509,0.526257,-0.0773244 +47,1,11.0666,-0.980156,-1.23946,1.02451,0.526833,-0.0750042 +48,1,11.0596,-0.979559,-1.23935,1.02407,0.528178,-0.0729994 +49,1,11.0648,-0.979921,-1.23823,1.02536,0.527009,-0.0780993 +50,1,11.0644,-0.979864,-1.23785,1.02532,0.527828,-0.0774264 +51,1,11.0644,-0.97994,-1.2392,1.02556,0.527596,-0.0773505 +52,1,11.0702,-0.980328,-1.2402,1.02575,0.52688,-0.0779361 +53,1,11.0663,-0.980035,-1.23953,1.02528,0.52774,-0.0782881 +54,1,11.0673,-0.980692,-1.23889,1.02526,0.526324,-0.0760211 +55,1,11.0631,-0.980008,-1.23901,1.02413,0.527211,-0.07438 +56,1,11.0598,-0.979826,-1.23838,1.02599,0.528379,-0.0778059 +57,1,11.0629,-0.979925,-1.24035,1.02483,0.528327,-0.0744678 +58,1,11.0721,-0.980812,-1.24003,1.02514,0.526953,-0.0784518 +59,1,11.0699,-0.980411,-1.2386,1.02485,0.526313,-0.0768156 +60,1,11.0676,-0.980138,-1.23922,1.02474,0.526912,-0.0777836 +61,1,11.0724,-0.980817,-1.23994,1.02492,0.527632,-0.0779458 +62,1,11.057,-0.979447,-1.23879,1.02451,0.529601,-0.0746845 +63,1,11.0669,-0.980207,-1.24039,1.02542,0.526801,-0.0777565 +64,1,11.0733,-0.980869,-1.2403,1.02593,0.525954,-0.0784081 +65,1,11.0644,-0.979869,-1.23852,1.02475,0.527464,-0.0748783 +66,1,11.0683,-0.980237,-1.2396,1.0247,0.527261,-0.0772122 +67,1,11.0633,-0.97998,-1.24007,1.02515,0.527752,-0.0768621 +68,1,11.0651,-0.980331,-1.23977,1.02483,0.527673,-0.0777072 +69,1,11.0661,-0.980122,-1.24002,1.02489,0.528969,-0.0781109 +70,1,11.0634,-0.979985,-1.23905,1.02673,0.528128,-0.0789966 +71,1,11.063,-0.980046,-1.23946,1.02566,0.527713,-0.0757801 +72,1,11.06,-0.97987,-1.23931,1.0249,0.529077,-0.0766846 +73,1,11.0635,-0.980093,-1.24026,1.02566,0.527676,-0.0766011 +74,1,11.058,-0.979577,-1.23964,1.0234,0.528867,-0.0727299 +75,1,11.0665,-0.979714,-1.2397,1.02544,0.526756,-0.0801339 +76,1,11.0652,-0.980167,-1.2398,1.02495,0.527736,-0.0756067 +77,1,11.069,-0.980569,-1.24008,1.02563,0.526783,-0.0788516 +78,1,11.0673,-0.980909,-1.24221,1.02497,0.528141,-0.0764055 +79,1,11.0644,-0.980129,-1.24543,1.02591,0.52781,-0.0775249 +80,1,11.0702,-0.980289,-1.24158,1.02496,0.526936,-0.0771435 +81,1,11.0722,-0.980336,-1.2358,1.02536,0.525561,-0.0795292 +82,1,11.0587,-0.980339,-1.23727,1.0247,0.528498,-0.0745648 +83,1,11.0626,-0.980219,-1.2454,1.02446,0.527544,-0.0773174 +84,1,11.075,-0.980513,-1.24859,1.0256,0.525434,-0.0804219 +85,1,11.0751,-0.980901,-1.24124,1.02521,0.527658,-0.0751499 +86,1,11.0681,-0.980145,-1.23412,1.02503,0.526564,-0.0779146 +87,1,11.0613,-0.980379,-1.23944,1.02419,0.528988,-0.0748587 +88,1,11.0692,-0.980888,-1.24775,1.02585,0.525483,-0.0798684 +89,1,11.0712,-0.980138,-1.24462,1.02546,0.527344,-0.0784139 +90,1,11.0697,-0.980472,-1.23791,1.0244,0.52713,-0.0748005 +91,1,11.0675,-0.981213,-1.23834,1.02527,0.526908,-0.076529 +92,1,11.0667,-0.980573,-1.24593,1.02493,0.526786,-0.0764799 +93,1,11.07,-0.980177,-1.24629,1.02524,0.527653,-0.0768784 +94,1,11.0697,-0.980445,-1.239,1.02445,0.52728,-0.0750349 +95,1,11.0709,-0.9807,-1.23655,1.02505,0.525554,-0.076849 +96,1,11.065,-0.980653,-1.241,1.02532,0.528078,-0.07506 +97,1,11.0679,-0.980629,-1.24731,1.02607,0.526665,-0.0777279 +98,1,11.0767,-0.980795,-1.24627,1.02653,0.525323,-0.0807253 +99,1,11.0748,-0.980903,-1.23476,1.02542,0.525457,-0.0774746 +100,1,11.0613,-0.980544,-1.23879,1.02444,0.528207,-0.0740752 +101,1,11.0675,-0.981132,-1.2476,1.02423,0.525957,-0.0765553 +102,1,11.0739,-0.980501,-1.24496,1.02591,0.526048,-0.0794051 +103,1,11.0686,-0.980497,-1.23946,1.02536,0.526968,-0.0785224 +104,1,11.0625,-0.980926,-1.23699,1.02539,0.527801,-0.0758371 +105,1,11.0626,-0.980201,-1.24103,1.02388,0.527078,-0.0760273 +106,1,11.0639,-0.979584,-1.24488,1.02484,0.526899,-0.0764327 +107,1,11.0711,-0.980704,-1.24038,1.02583,0.526402,-0.0786271 +108,1,11.0689,-0.980275,-1.24104,1.02448,0.526695,-0.0747383 +109,1,11.0686,-0.980149,-1.24101,1.02556,0.527559,-0.0770928 +110,1,11.0596,-0.980084,-1.23961,1.02487,0.52842,-0.075845 +111,1,11.0615,-0.979901,-1.24119,1.02506,0.527947,-0.0737635 +112,1,11.0646,-0.98032,-1.2374,1.02494,0.527728,-0.077815 +113,1,11.0635,-0.980385,-1.24052,1.02358,0.527257,-0.0731826 +114,1,11.0586,-0.980006,-1.24026,1.02525,0.528748,-0.0764746 +115,1,11.0664,-0.980302,-1.24017,1.02454,0.527106,-0.0766414 +116,1,11.059,-0.980102,-1.24173,1.02467,0.527899,-0.0746839 +117,1,11.0688,-0.980662,-1.23938,1.02539,0.52723,-0.0785868 +118,1,11.0645,-0.980179,-1.23903,1.02606,0.526287,-0.0789651 +119,1,11.0719,-0.980724,-1.24084,1.02414,0.526765,-0.0763835 +120,1,11.0576,-0.979577,-1.23908,1.02492,0.528658,-0.0743765 +121,1,11.0642,-0.980915,-1.24332,1.02589,0.527176,-0.0792062 +122,1,11.0617,-0.980245,-1.24287,1.02497,0.528036,-0.0758097 +123,1,11.0644,-0.98016,-1.23964,1.02501,0.52792,-0.0758145 +124,1,11.0773,-0.981316,-1.23759,1.02547,0.525527,-0.0798647 +125,1,11.062,-0.979978,-1.23924,1.02446,0.528536,-0.0763952 +126,1,11.0723,-0.980373,-1.24721,1.02622,0.525795,-0.078868 +127,1,11.071,-0.980967,-1.24321,1.02623,0.527515,-0.0779596 +128,1,11.0639,-0.98008,-1.23883,1.02494,0.527381,-0.0767112 +129,1,11.0699,-0.980299,-1.23559,1.02575,0.525176,-0.0787304 +130,1,11.0625,-0.980405,-1.23706,1.02543,0.52807,-0.0771837 +131,1,11.0608,-0.979872,-1.24393,1.02581,0.528033,-0.0779495 +132,1,11.0623,-0.979707,-1.24331,1.02474,0.527591,-0.0763278 +133,1,11.062,-0.979846,-1.2417,1.02481,0.528229,-0.0754029 +134,1,11.0693,-0.980409,-1.23784,1.02505,0.527341,-0.0759851 +135,1,11.0663,-0.980244,-1.23591,1.02506,0.525634,-0.0772758 +136,1,11.0631,-0.979872,-1.23996,1.02503,0.52696,-0.0773571 +137,1,11.0654,-0.979967,-1.24324,1.02694,0.527096,-0.0788114 +138,1,11.0664,-0.980062,-1.24284,1.02626,0.528014,-0.0781035 +139,1,11.0686,-0.980442,-1.23969,1.02598,0.527275,-0.0803571 +140,1,11.0653,-0.979801,-1.23712,1.02487,0.527513,-0.0764538 +141,1,11.0678,-0.980222,-1.23813,1.025,0.526225,-0.0766698 +142,1,11.0636,-0.979613,-1.2399,1.02463,0.527543,-0.0764358 +143,1,11.0652,-0.979892,-1.2423,1.02521,0.527035,-0.077039 +144,1,11.0616,-0.979996,-1.24042,1.02447,0.529425,-0.0747026 +145,1,11.0701,-0.980019,-1.23924,1.02491,0.526844,-0.0780144 +146,1,11.0726,-0.980459,-1.23864,1.02508,0.526324,-0.0781392 +147,1,11.0598,-0.979504,-1.23851,1.02512,0.527987,-0.0753357 +147,21,36.0228,17.8933,-12.513,0.514434,0.871709,-0.985929 +148,1,11.0617,-0.979455,-1.24073,1.025,0.528412,-0.0759404 +149,1,11.0643,-0.979687,-1.24132,1.02536,0.527869,-0.0788414 +150,1,11.0682,-0.980152,-1.23988,1.0254,0.527015,-0.077718 +151,1,11.0624,-0.979509,-1.23901,1.02556,0.527774,-0.0779285 +152,1,11.0648,-0.980073,-1.24105,1.0242,0.528407,-0.0741378 +153,1,11.0561,-0.979665,-1.23987,1.02446,0.529541,-0.0731572 +154,1,11.0634,-0.980298,-1.24275,1.02578,0.528176,-0.076598 +155,1,11.0621,-0.979892,-1.24007,1.02454,0.528486,-0.0747352 +156,1,11.0631,-0.979122,-1.23913,1.02437,0.527347,-0.0760442 +157,1,11.0689,-0.9803,-1.23875,1.02551,0.527336,-0.0789604 +158,1,11.0662,-0.980272,-1.23935,1.02456,0.527439,-0.0775954 +159,1,11.0601,-0.979556,-1.24193,1.02426,0.528781,-0.0744846 +160,1,11.07,-0.98068,-1.24687,1.02581,0.526652,-0.0781271 +161,1,11.0661,-0.979387,-1.24314,1.02507,0.526533,-0.0779592 +162,1,11.0651,-0.979557,-1.24084,1.02447,0.527199,-0.0741689 +163,1,11.0644,-0.979195,-1.23706,1.02519,0.527767,-0.076107 +164,1,11.0658,-0.979538,-1.23956,1.02509,0.527125,-0.077317 +165,1,11.0637,-0.979266,-1.24518,1.02531,0.526673,-0.0761374 +166,1,11.0648,-0.979586,-1.2447,1.02583,0.526349,-0.0762456 +167,1,11.0689,-0.980128,-1.24263,1.02416,0.526885,-0.0740555 +168,1,11.0751,-0.980813,-1.23877,1.02489,0.526013,-0.0778741 +169,1,11.0683,-0.980471,-1.23645,1.02403,0.527028,-0.0752576 +170,1,11.0598,-0.97947,-1.24139,1.02502,0.528214,-0.0764134 +171,1,11.0612,-0.979568,-1.24424,1.0249,0.525841,-0.0764159 +172,1,11.0609,-0.980146,-1.24404,1.02575,0.525836,-0.0782888 +173,1,11.0606,-0.979687,-1.23998,1.0252,0.528267,-0.0738923 +174,1,11.0583,-0.979505,-1.23723,1.02501,0.528695,-0.0752119 +175,1,11.0632,-0.979794,-1.23933,1.02496,0.528019,-0.077783 +176,1,11.0634,-0.979867,-1.24222,1.02525,0.528172,-0.078256 +177,1,11.0595,-0.979227,-1.24377,1.02531,0.526769,-0.0784264 +178,1,11.0669,-0.979677,-1.24246,1.02604,0.527625,-0.0768311 +179,1,11.0698,-0.980047,-1.24045,1.02381,0.526744,-0.0756029 +180,1,11.0686,-0.979882,-1.23909,1.02522,0.526663,-0.0798414 +181,1,11.0642,-0.980002,-1.24037,1.02483,0.52719,-0.075476 +182,1,11.07,-0.979932,-1.24409,1.02635,0.524812,-0.0788477 +183,1,11.063,-0.979371,-1.2439,1.02549,0.526693,-0.0753887 +184,1,11.0708,-0.979979,-1.24155,1.02436,0.52691,-0.074841 +185,1,11.0669,-0.97966,-1.23963,1.02486,0.52697,-0.0769795 +186,1,11.0623,-0.979239,-1.23979,1.02503,0.527956,-0.0772844 +187,1,11.0641,-0.979714,-1.24232,1.02513,0.528317,-0.0762878 +188,1,11.0669,-0.980164,-1.24402,1.02494,0.526474,-0.0787171 +189,1,11.0646,-0.980108,-1.24248,1.02535,0.528108,-0.0770498 +190,1,11.0682,-0.980553,-1.23983,1.02497,0.527173,-0.0784175 +191,1,11.0738,-0.98051,-1.237,1.02426,0.526537,-0.0773113 +192,1,11.0689,-0.979546,-1.24355,1.02472,0.526903,-0.0772132 +193,1,11.0702,-0.979409,-1.24696,1.02553,0.526028,-0.0798072 +194,1,11.0653,-0.979125,-1.24191,1.02392,0.527551,-0.0749812 +195,1,11.0681,-0.979469,-1.24006,1.02527,0.526972,-0.0781505 +196,1,11.0731,-0.979921,-1.23703,1.0244,0.525421,-0.0777861 +197,1,11.0611,-0.978923,-1.23954,1.02535,0.527171,-0.0762243 +198,1,11.0605,-0.978689,-1.24198,1.02456,0.527839,-0.0763429 +199,1,11.0676,-0.979415,-1.24409,1.02445,0.526779,-0.0765054 +200,1,11.0697,-0.979542,-1.24154,1.02469,0.527069,-0.0773297 +201,1,11.0718,-0.979737,-1.23742,1.02428,0.525152,-0.0776375 +202,1,11.0674,-0.979453,-1.23882,1.02543,0.526556,-0.0782304 +203,1,11.0661,-0.979367,-1.24003,1.02375,0.526923,-0.0752468 +204,1,11.0618,-0.978832,-1.24234,1.02354,0.52743,-0.073892 +205,1,11.0631,-0.978747,-1.24203,1.02455,0.527571,-0.0733868 +206,1,11.0655,-0.979225,-1.2401,1.02451,0.527495,-0.0766848 +207,1,11.0693,-0.979095,-1.23918,1.0255,0.526047,-0.0795782 +208,1,11.0647,-0.979476,-1.23962,1.02477,0.52748,-0.0759159 +209,1,11.0641,-0.978912,-1.2419,1.02534,0.527378,-0.0754713 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_april.txt new file mode 100644 index 0000000..785415a --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_april.txt @@ -0,0 +1,221 @@ +iter,id,x,y,z,r,p,y +0,1,13.6651,-1.26068,-1.94913,1.02472,0.519083,-0.122633 +1,1,13.6729,-1.26145,-1.9464,1.02579,0.518058,-0.122737 +2,1,13.6752,-1.26173,-1.9469,1.02541,0.517652,-0.122813 +3,1,13.6616,-1.26029,-1.94762,1.02562,0.521683,-0.125364 +4,1,13.6642,-1.26056,-1.94937,1.02471,0.519968,-0.122413 +5,1,13.6706,-1.26108,-1.9477,1.02594,0.518977,-0.122324 +6,1,13.6673,-1.26093,-1.94514,1.02484,0.518729,-0.123268 +7,1,13.6604,-1.26009,-1.94642,1.02741,0.520055,-0.125383 +8,1,13.6632,-1.26045,-1.94895,1.02581,0.522352,-0.121121 +9,1,13.673,-1.2615,-1.9489,1.02578,0.520077,-0.123393 +10,1,13.6725,-1.26136,-1.94669,1.02421,0.518314,-0.122158 +11,1,13.671,-1.26123,-1.94716,1.02413,0.519261,-0.119487 +12,1,13.6643,-1.26061,-1.94841,1.02438,0.520024,-0.120466 +13,1,13.6686,-1.261,-1.94903,1.02814,0.519184,-0.129626 +14,1,13.6702,-1.2614,-1.94678,1.02634,0.520132,-0.126029 +15,1,13.6718,-1.26136,-1.94688,1.02595,0.519491,-0.12491 +16,1,13.6618,-1.2604,-1.9473,1.02568,0.519836,-0.123453 +17,1,13.6638,-1.26085,-1.94858,1.02587,0.519201,-0.124331 +18,1,13.6608,-1.26078,-1.94585,1.02589,0.521578,-0.12298 +19,1,13.667,-1.26108,-1.94647,1.02466,0.518226,-0.122189 +20,1,13.673,-1.26127,-1.94867,1.02607,0.517896,-0.12508 +21,1,13.6716,-1.2614,-1.94931,1.02647,0.519891,-0.126472 +22,1,13.6656,-1.26099,-1.94698,1.02551,0.51992,-0.121348 +23,1,13.661,-1.26046,-1.94541,1.02504,0.519875,-0.122207 +24,1,13.6713,-1.26176,-1.94793,1.02666,0.520035,-0.128013 +25,1,13.6713,-1.26145,-1.94909,1.02619,0.519798,-0.12479 +26,1,13.6594,-1.26046,-1.94635,1.02587,0.521434,-0.123785 +27,1,13.6677,-1.26137,-1.94623,1.02492,0.5198,-0.122393 +28,1,13.6733,-1.26143,-1.94797,1.0248,0.518057,-0.120944 +29,1,13.6669,-1.26126,-1.94809,1.02616,0.519235,-0.124089 +30,1,13.6568,-1.2605,-1.9466,1.02525,0.52063,-0.121084 +31,1,13.6673,-1.26122,-1.94666,1.02582,0.519301,-0.12472 +32,1,13.6659,-1.26113,-1.94751,1.02406,0.519365,-0.117151 +33,1,13.658,-1.26018,-1.94651,1.02662,0.520959,-0.124192 +34,1,13.6615,-1.26079,-1.94719,1.02569,0.520019,-0.122947 +35,1,13.6625,-1.26082,-1.94682,1.0252,0.520385,-0.121918 +36,1,13.6678,-1.26153,-1.94726,1.02704,0.519878,-0.124559 +37,1,13.667,-1.26101,-1.94761,1.02561,0.519958,-0.123666 +38,1,13.6726,-1.26219,-1.94848,1.02542,0.518418,-0.124165 +39,1,13.6706,-1.26143,-1.94708,1.02727,0.519545,-0.125601 +40,1,13.6581,-1.26036,-1.94564,1.02538,0.520282,-0.12418 +41,1,13.6684,-1.26159,-1.94804,1.02559,0.520034,-0.121349 +42,1,13.6607,-1.26081,-1.94695,1.0261,0.520432,-0.122785 +43,1,13.6654,-1.26148,-1.94698,1.02695,0.520225,-0.125076 +44,1,13.6683,-1.2617,-1.94737,1.0257,0.518932,-0.124382 +45,1,13.6663,-1.26131,-1.94746,1.02747,0.520333,-0.126293 +46,1,13.6759,-1.26232,-1.94931,1.02624,0.518096,-0.122882 +47,1,13.6622,-1.26104,-1.94659,1.02525,0.52089,-0.122384 +48,1,13.6661,-1.26172,-1.94634,1.02725,0.519438,-0.126161 +49,1,13.676,-1.26215,-1.94866,1.02535,0.517971,-0.123757 +50,1,13.6725,-1.26191,-1.94895,1.02488,0.520085,-0.125718 +51,1,13.6612,-1.261,-1.94631,1.02641,0.519137,-0.125367 +52,1,13.6652,-1.26154,-1.94656,1.02649,0.519757,-0.124328 +53,1,13.6698,-1.26184,-1.94763,1.02599,0.518685,-0.123997 +54,1,13.6654,-1.26151,-1.94735,1.02698,0.520155,-0.124284 +55,1,13.6703,-1.26226,-1.94775,1.02551,0.518439,-0.125376 +56,1,13.6713,-1.26191,-1.94779,1.02626,0.519785,-0.123622 +57,1,13.6574,-1.2605,-1.9459,1.02743,0.520315,-0.123681 +58,1,13.6608,-1.26095,-1.94701,1.0265,0.520276,-0.122606 +59,1,13.6677,-1.26162,-1.94762,1.02667,0.520209,-0.124675 +60,1,13.6615,-1.26112,-1.94645,1.02468,0.521103,-0.119604 +61,1,13.6648,-1.26123,-1.94655,1.02641,0.519534,-0.126153 +62,1,13.6614,-1.2613,-1.94682,1.02726,0.521344,-0.124941 +63,1,13.6616,-1.26119,-1.94697,1.02632,0.519737,-0.122427 +64,1,13.6746,-1.26241,-1.94792,1.02645,0.518866,-0.127895 +65,1,13.6677,-1.26189,-1.94725,1.02675,0.518445,-0.125178 +66,1,13.6682,-1.26187,-1.94778,1.02769,0.519245,-0.126605 +67,1,13.6653,-1.26145,-1.94709,1.02562,0.519214,-0.124641 +68,1,13.666,-1.26161,-1.94698,1.02599,0.519462,-0.12441 +69,1,13.6747,-1.26224,-1.94833,1.02664,0.518017,-0.126236 +70,1,13.6653,-1.26164,-1.94702,1.02672,0.519802,-0.127806 +71,1,13.66,-1.26105,-1.94692,1.02616,0.521161,-0.12363 +72,1,13.6712,-1.26207,-1.94797,1.0261,0.519193,-0.123616 +73,1,13.667,-1.26168,-1.94741,1.02833,0.519441,-0.127663 +74,1,13.6653,-1.26191,-1.94772,1.02457,0.520102,-0.121187 +75,1,13.6665,-1.262,-1.94788,1.02632,0.51904,-0.12354 +76,1,13.6729,-1.26196,-1.9483,1.02685,0.518856,-0.126231 +77,1,13.6708,-1.26233,-1.94831,1.02515,0.519596,-0.123089 +78,1,13.666,-1.26184,-1.94702,1.02663,0.519297,-0.124885 +79,1,13.6659,-1.26189,-1.94756,1.02484,0.519754,-0.122328 +80,1,13.6624,-1.26142,-1.94702,1.02685,0.520461,-0.125358 +81,1,13.6682,-1.26209,-1.94768,1.02592,0.520387,-0.124972 +82,1,13.6696,-1.26189,-1.94765,1.02559,0.518659,-0.125857 +83,1,13.6665,-1.26139,-1.94757,1.02675,0.519161,-0.126506 +84,1,13.6735,-1.26249,-1.94898,1.02478,0.518345,-0.121901 +85,1,13.6631,-1.26161,-1.94652,1.02601,0.519808,-0.12315 +86,1,13.662,-1.2614,-1.94672,1.02529,0.518831,-0.122551 +87,1,13.6618,-1.26162,-1.94733,1.02555,0.520594,-0.121198 +88,1,13.6603,-1.26097,-1.94697,1.02668,0.520662,-0.123835 +89,1,13.6678,-1.26202,-1.94699,1.0266,0.519847,-0.124338 +90,1,13.6635,-1.26154,-1.94693,1.02625,0.52023,-0.125097 +91,1,13.6641,-1.26175,-1.94673,1.02614,0.520799,-0.123119 +92,1,13.6731,-1.26238,-1.94826,1.02776,0.519351,-0.126789 +93,1,13.6694,-1.26219,-1.94742,1.02518,0.519083,-0.122147 +94,1,13.6669,-1.26201,-1.94702,1.02603,0.519654,-0.121743 +95,1,13.6652,-1.26147,-1.94719,1.02704,0.519329,-0.126856 +96,1,13.666,-1.26186,-1.94721,1.02665,0.52011,-0.124576 +97,1,13.666,-1.26177,-1.947,1.02716,0.520173,-0.125645 +98,1,13.6666,-1.26166,-1.9472,1.02674,0.521291,-0.125238 +99,1,13.6722,-1.26225,-1.9476,1.0258,0.51946,-0.124781 +100,1,13.6706,-1.26208,-1.94749,1.02678,0.519859,-0.126438 +101,1,13.6648,-1.26174,-1.94695,1.02666,0.519265,-0.125529 +102,1,13.6628,-1.26142,-1.94641,1.02547,0.520671,-0.124103 +103,1,13.6746,-1.26228,-1.94809,1.02661,0.517966,-0.125155 +104,1,13.6667,-1.26181,-1.947,1.02798,0.520809,-0.126712 +105,1,13.6694,-1.26236,-1.94757,1.02588,0.519994,-0.124472 +106,1,13.6648,-1.26181,-1.94652,1.02554,0.519848,-0.123907 +107,1,13.6732,-1.26228,-1.94759,1.02718,0.51793,-0.126791 +108,1,13.6675,-1.26198,-1.94731,1.026,0.519441,-0.12461 +109,1,13.6658,-1.26166,-1.94668,1.02513,0.520283,-0.121902 +110,1,13.664,-1.26169,-1.94647,1.02671,0.519498,-0.124126 +111,1,13.6664,-1.26199,-1.94738,1.02629,0.519693,-0.123331 +112,1,13.6665,-1.26179,-1.94656,1.02696,0.519364,-0.126438 +113,1,13.6699,-1.26217,-1.9471,1.02515,0.519596,-0.123969 +114,1,13.6676,-1.26213,-1.9471,1.02673,0.520532,-0.126102 +115,1,13.6729,-1.26227,-1.94763,1.02667,0.519098,-0.12465 +116,1,13.6724,-1.26238,-1.94797,1.02672,0.519513,-0.124005 +117,1,13.6722,-1.26236,-1.94748,1.02619,0.519436,-0.126086 +118,1,13.6695,-1.26203,-1.94762,1.02553,0.519045,-0.123554 +119,1,13.6752,-1.26265,-1.94847,1.02677,0.518908,-0.127536 +120,1,13.6647,-1.26153,-1.9465,1.02745,0.519858,-0.127409 +121,1,13.6665,-1.26182,-1.94721,1.02683,0.520125,-0.126423 +122,1,13.6671,-1.2622,-1.94725,1.02563,0.519535,-0.121626 +123,1,13.6714,-1.26264,-1.94747,1.0256,0.519555,-0.123818 +124,1,13.6677,-1.26213,-1.94734,1.02644,0.519557,-0.124136 +125,1,13.6663,-1.26191,-1.94692,1.02648,0.519518,-0.124056 +126,1,13.6712,-1.26251,-1.94784,1.02589,0.51821,-0.124551 +127,1,13.6638,-1.26145,-1.94666,1.02607,0.518818,-0.124305 +128,1,13.671,-1.26204,-1.94772,1.02666,0.517652,-0.125565 +129,1,13.6614,-1.26165,-1.94668,1.02604,0.520924,-0.123958 +130,1,13.662,-1.26161,-1.94645,1.0259,0.521103,-0.123628 +131,1,13.6639,-1.26176,-1.94629,1.02524,0.519206,-0.12202 +132,1,13.671,-1.26246,-1.94779,1.02605,0.517913,-0.125804 +133,1,13.6731,-1.26234,-1.94732,1.02665,0.518099,-0.125854 +134,1,13.6701,-1.26226,-1.94733,1.02451,0.519943,-0.121206 +135,1,13.6706,-1.26252,-1.94742,1.02717,0.519089,-0.126486 +136,1,13.6655,-1.26204,-1.94656,1.02625,0.520181,-0.123808 +137,1,13.6754,-1.26236,-1.94791,1.02665,0.519402,-0.125825 +138,1,13.6708,-1.26219,-1.94737,1.0264,0.519528,-0.125718 +139,1,13.6586,-1.2614,-1.94515,1.0246,0.521278,-0.119324 +140,1,13.6664,-1.26171,-1.94629,1.02583,0.519376,-0.123129 +141,1,13.6682,-1.26218,-1.94708,1.02521,0.519793,-0.121772 +142,1,13.6638,-1.26164,-1.94615,1.02687,0.520104,-0.125849 +143,1,13.6665,-1.26239,-1.94619,1.02659,0.519801,-0.123659 +144,1,13.662,-1.26157,-1.94598,1.026,0.519858,-0.122998 +145,1,13.6686,-1.26227,-1.94692,1.02511,0.520869,-0.122485 +146,1,13.6667,-1.26171,-1.94633,1.02515,0.519674,-0.122113 +147,1,13.6726,-1.26261,-1.9473,1.02578,0.51837,-0.125616 +148,1,13.6774,-1.26289,-1.94774,1.02766,0.518438,-0.129053 +149,1,13.6702,-1.26205,-1.94678,1.02552,0.519417,-0.121422 +150,1,13.6542,-1.26072,-1.94517,1.02485,0.520773,-0.120571 +151,1,13.6608,-1.26145,-1.94591,1.02527,0.520424,-0.123066 +152,1,13.6662,-1.26183,-1.94583,1.02646,0.519988,-0.125656 +153,1,13.6605,-1.26148,-1.94586,1.02543,0.52121,-0.124371 +154,1,13.6666,-1.26187,-1.94661,1.0243,0.519482,-0.122331 +155,1,13.6676,-1.26198,-1.94633,1.0253,0.518881,-0.122461 +156,1,13.6707,-1.26208,-1.9472,1.02671,0.518674,-0.127154 +157,1,13.6611,-1.26165,-1.94613,1.02579,0.520139,-0.123898 +158,1,13.6734,-1.26263,-1.9478,1.02609,0.51868,-0.12442 +159,1,13.6646,-1.26187,-1.9463,1.02498,0.520654,-0.124021 +160,1,13.6639,-1.26177,-1.94636,1.02644,0.519436,-0.124063 +161,1,13.66,-1.26145,-1.94545,1.02568,0.52015,-0.122704 +162,1,13.6619,-1.26149,-1.94589,1.0267,0.518944,-0.126029 +163,1,13.6669,-1.26176,-1.94664,1.02594,0.520192,-0.122693 +164,1,13.6701,-1.26236,-1.94692,1.0258,0.519387,-0.122318 +165,1,13.6726,-1.26233,-1.94737,1.02608,0.517714,-0.125985 +166,1,13.6752,-1.26295,-1.948,1.02717,0.518535,-0.127223 +167,1,13.6711,-1.2623,-1.94702,1.02542,0.519436,-0.124064 +168,1,13.6763,-1.26288,-1.94792,1.02604,0.518506,-0.125784 +169,1,13.6567,-1.26143,-1.94503,1.0255,0.520999,-0.123041 +170,1,13.6751,-1.26273,-1.94743,1.02577,0.517617,-0.122218 +171,1,13.669,-1.26234,-1.94705,1.02576,0.519918,-0.12358 +172,1,13.6654,-1.26186,-1.9462,1.02664,0.518912,-0.124462 +173,1,13.6703,-1.26227,-1.94716,1.02425,0.519131,-0.121197 +174,1,13.6632,-1.26199,-1.94641,1.02604,0.520377,-0.123328 +175,1,13.6674,-1.26179,-1.94703,1.02726,0.519889,-0.125436 +176,1,13.6649,-1.26232,-1.94595,1.02536,0.520241,-0.122043 +177,1,13.6627,-1.26181,-1.94624,1.02452,0.520883,-0.120347 +178,1,13.6713,-1.26232,-1.94711,1.02526,0.519501,-0.121794 +179,1,13.6664,-1.26196,-1.94647,1.02596,0.519383,-0.124224 +180,1,13.6613,-1.26161,-1.94592,1.02543,0.520362,-0.119161 +181,1,13.6632,-1.26151,-1.94643,1.02538,0.520346,-0.12309 +182,1,13.6646,-1.26151,-1.94615,1.02703,0.518855,-0.125487 +183,1,13.6725,-1.26243,-1.94734,1.02687,0.519078,-0.127338 +184,1,13.6747,-1.26291,-1.94721,1.02598,0.51945,-0.123289 +185,1,13.6679,-1.262,-1.94651,1.02641,0.518799,-0.123481 +186,1,13.6669,-1.26231,-1.94648,1.02668,0.519606,-0.126142 +187,1,13.6624,-1.26203,-1.94596,1.02623,0.520287,-0.122022 +188,1,13.6634,-1.26169,-1.94601,1.02653,0.520694,-0.124265 +189,1,13.6738,-1.26292,-1.94777,1.02665,0.518625,-0.126427 +190,1,13.6721,-1.26269,-1.94677,1.02588,0.519528,-0.124398 +191,1,13.672,-1.26287,-1.94722,1.02639,0.519245,-0.126542 +192,1,13.6729,-1.26264,-1.94733,1.02721,0.518664,-0.126649 +193,1,13.6665,-1.26205,-1.94634,1.02567,0.519035,-0.124204 +194,1,13.6728,-1.26249,-1.94748,1.02659,0.520425,-0.123201 +195,1,13.6685,-1.26246,-1.94649,1.02604,0.519243,-0.123105 +196,1,13.6687,-1.26237,-1.94707,1.02693,0.519015,-0.124542 +197,1,13.6724,-1.26249,-1.94714,1.02555,0.519038,-0.124071 +198,1,13.6625,-1.26151,-1.9458,1.02514,0.519698,-0.122558 +199,1,13.67,-1.26227,-1.94671,1.02564,0.520268,-0.123848 +200,1,13.6617,-1.26194,-1.94552,1.02543,0.521293,-0.122987 +201,1,13.6708,-1.26259,-1.94703,1.02682,0.519421,-0.127129 +202,1,13.6645,-1.26239,-1.94663,1.02564,0.520689,-0.123471 +203,1,13.6796,-1.26285,-1.94784,1.02695,0.517897,-0.127894 +204,1,13.674,-1.26259,-1.94745,1.02582,0.517803,-0.123965 +205,1,13.6713,-1.26242,-1.94731,1.02528,0.518363,-0.123072 +206,1,13.6696,-1.26236,-1.94693,1.02536,0.51963,-0.123091 +207,1,13.6694,-1.26204,-1.94664,1.02562,0.52024,-0.124288 +208,1,13.6713,-1.26244,-1.94701,1.02565,0.519758,-0.124174 +209,1,13.6724,-1.26269,-1.94683,1.02531,0.518499,-0.125347 +210,1,13.6704,-1.26256,-1.94676,1.02614,0.520235,-0.124684 +211,1,13.6768,-1.26318,-1.94793,1.02509,0.518497,-0.12138 +212,1,13.6666,-1.26223,-1.94598,1.02443,0.518091,-0.121742 +213,1,13.6706,-1.2621,-1.94708,1.02549,0.518674,-0.124853 +214,1,13.6843,-1.26374,-1.94858,1.02589,0.517782,-0.126017 +215,1,13.661,-1.26191,-1.94507,1.02514,0.519957,-0.124292 +216,1,13.6634,-1.26206,-1.94568,1.02533,0.520243,-0.12015 +217,1,13.6676,-1.26191,-1.94631,1.02539,0.519575,-0.124654 +218,1,13.6699,-1.26272,-1.94641,1.02649,0.518236,-0.127302 +219,1,13.6715,-1.26235,-1.94667,1.02607,0.518432,-0.126172 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_other.txt new file mode 100644 index 0000000..23506b9 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-5/pose_other.txt @@ -0,0 +1,224 @@ +iter,id,x,y,z,r,p,y +0,1,0.983824,1.24308,11.1432,2.7879,0.396259,-0.932167 +1,1,0.984696,1.24256,11.1537,2.78544,0.393628,-0.932416 +2,1,0.984838,1.24227,11.1542,2.78643,0.392497,-0.931944 +3,1,0.983763,1.24494,11.1457,2.78869,0.396298,-0.932523 +3,9,-12.452,-7.30195,36.4767,1.05361,2.74519,-1.64148 +4,1,0.983766,1.24654,11.1434,2.78554,0.395379,-0.931775 +5,1,0.984458,1.24607,11.1483,2.78862,0.395612,-0.93191 +6,1,0.984153,1.24296,11.1494,2.78776,0.395807,-0.932015 +7,1,0.984254,1.24186,11.1507,2.78863,0.39465,-0.932129 +8,1,0.983708,1.24293,11.1429,2.78754,0.396648,-0.932186 +9,1,0.984257,1.24475,11.1491,2.78721,0.395698,-0.931858 +10,1,0.98317,1.2451,11.1407,2.78796,0.397643,-0.931903 +11,1,0.983777,1.24395,11.1468,2.78634,0.395943,-0.932732 +12,1,0.984205,1.24227,11.1506,2.79021,0.395957,-0.933207 +13,1,0.98304,1.24113,11.1387,2.78734,0.397784,-0.931559 +14,1,0.98345,1.24324,11.1415,2.78786,0.397309,-0.932183 +15,1,0.983445,1.24598,11.1421,2.786,0.39735,-0.931877 +16,1,0.983879,1.24599,11.1482,2.78676,0.395787,-0.931703 +17,1,0.982757,1.24385,11.1404,2.78772,0.397678,-0.9321 +18,1,0.983751,1.24369,11.1504,2.78702,0.394289,-0.932238 +19,1,0.983036,1.24281,11.1404,2.78852,0.397933,-0.932612 +20,1,0.983749,1.24547,11.1503,2.78804,0.396139,-0.932173 +21,1,0.983941,1.24597,11.1531,2.7867,0.395226,-0.932112 +22,1,0.983022,1.24443,11.1425,2.79044,0.398184,-0.931992 +23,1,0.983802,1.24351,11.1485,2.7883,0.396328,-0.932003 +24,1,0.983687,1.24344,11.1478,2.78833,0.396372,-0.93284 +25,1,0.983332,1.2438,11.1419,2.78688,0.39672,-0.931959 +26,1,0.983859,1.24521,11.1488,2.78653,0.394738,-0.932152 +27,1,0.983818,1.24463,11.1463,2.78757,0.3957,-0.931883 +28,1,0.983346,1.24317,11.1414,2.78808,0.397964,-0.932558 +29,1,0.983294,1.2431,11.1481,2.78814,0.396508,-0.932556 +30,1,0.983311,1.24336,11.1408,2.78745,0.396417,-0.93212 +31,1,0.983475,1.24482,11.144,2.78888,0.397719,-0.932017 +32,1,0.983114,1.24484,11.1415,2.78775,0.397689,-0.932143 +33,1,0.983969,1.24503,11.1534,2.78769,0.394852,-0.932321 +34,1,0.983229,1.24322,11.1463,2.78908,0.395495,-0.932918 +35,1,0.983745,1.24311,11.1502,2.78635,0.394871,-0.931686 +35,22,1.28861,9.01824,36.9999,1.53234,-0.31822,-0.691262 +36,1,0.983393,1.24424,11.1474,2.78995,0.396939,-0.931857 +37,1,0.983394,1.24461,11.1444,2.78736,0.396849,-0.932702 +38,1,0.983644,1.24396,11.1479,2.78697,0.395706,-0.931663 +39,1,0.98331,1.24371,11.141,2.78708,0.396798,-0.93235 +40,1,0.984034,1.24631,11.1502,2.7901,0.396477,-0.932561 +41,1,0.983823,1.24455,11.1473,2.78695,0.395859,-0.932269 +42,1,0.983529,1.24482,11.1475,2.78724,0.395695,-0.932095 +43,1,0.983564,1.24346,11.1477,2.78648,0.394676,-0.932237 +44,1,0.983194,1.24312,11.1457,2.78673,0.394847,-0.93153 +45,1,0.98359,1.24517,11.1472,2.78881,0.396964,-0.932397 +46,1,0.982724,1.24388,11.1414,2.7878,0.397915,-0.931421 +47,1,0.982878,1.24435,11.1453,2.78693,0.396178,-0.932377 +48,1,0.983182,1.24353,11.1465,2.78628,0.394835,-0.93144 +49,1,0.983462,1.24421,11.1489,2.78566,0.394392,-0.93178 +50,1,0.983092,1.24368,11.1442,2.78728,0.395711,-0.9319 +51,1,0.983443,1.24361,11.1499,2.78748,0.394904,-0.932031 +52,1,0.983102,1.2437,11.1463,2.78519,0.395477,-0.931835 +53,1,0.982826,1.24329,11.1462,2.78837,0.396386,-0.931558 +54,1,0.982437,1.24347,11.1413,2.78812,0.397548,-0.931889 +55,1,0.983226,1.2446,11.1487,2.78802,0.394872,-0.932331 +56,1,0.983053,1.24409,11.1466,2.78933,0.396599,-0.932281 +57,1,0.982447,1.24397,11.1395,2.79009,0.398785,-0.932103 +58,1,0.982793,1.24283,11.1445,2.78689,0.395262,-0.932049 +59,1,0.982749,1.24246,11.1443,2.78678,0.396211,-0.931922 +60,1,0.982816,1.24381,11.1441,2.78723,0.396247,-0.932307 +61,1,0.98324,1.24486,11.1504,2.78723,0.395289,-0.932537 +62,1,0.982909,1.24414,11.146,2.78623,0.395715,-0.931667 +63,1,0.983578,1.2435,11.1472,2.78905,0.395862,-0.932848 +64,1,0.982845,1.24357,11.1424,2.78947,0.397271,-0.931966 +65,1,0.982712,1.243,11.1397,2.78649,0.396744,-0.932339 +66,1,0.982783,1.24494,11.1425,2.78895,0.398325,-0.932291 +67,1,0.983702,1.24466,11.1521,2.78651,0.39488,-0.931715 +68,1,0.983317,1.24324,11.15,2.78811,0.395134,-0.932143 +69,1,0.983102,1.24393,11.1485,2.7869,0.394908,-0.931549 +70,1,0.983695,1.24455,11.1523,2.78633,0.39564,-0.931412 +71,1,0.982338,1.24342,11.1369,2.78781,0.399052,-0.931496 +72,1,0.983148,1.24508,11.1474,2.78735,0.395171,-0.932306 +73,1,0.983739,1.2449,11.153,2.78757,0.394458,-0.932878 +74,1,0.982751,1.24313,11.1442,2.7891,0.397288,-0.932353 +75,1,0.983068,1.24415,11.1476,2.78713,0.395795,-0.931545 +76,1,0.982873,1.24471,11.1433,2.78737,0.396469,-0.932005 +77,1,0.983212,1.24438,11.1449,2.78665,0.395863,-0.931443 +78,1,0.983022,1.24466,11.1461,2.78537,0.396597,-0.930918 +79,1,0.98289,1.24369,11.1436,2.78578,0.395975,-0.932725 +80,1,0.982946,1.24409,11.1431,2.78851,0.397236,-0.932893 +81,1,0.982811,1.244,11.1405,2.78654,0.39745,-0.93139 +82,1,0.983037,1.24496,11.144,2.78788,0.396652,-0.932659 +83,1,0.982473,1.24428,11.138,2.78963,0.399267,-0.931303 +84,1,0.982594,1.24432,11.1464,2.7853,0.393834,-0.931522 +85,1,0.983051,1.24441,11.1451,2.78835,0.397134,-0.932214 +86,1,0.983518,1.24479,11.1496,2.78655,0.394598,-0.932179 +87,1,0.98392,1.24699,11.1487,2.78744,0.396746,-0.931875 +88,1,0.983031,1.2501,11.1446,2.78714,0.3964,-0.932555 +89,1,0.983221,1.24626,11.1507,2.7876,0.395498,-0.932002 +90,1,0.983251,1.24044,11.1524,2.78649,0.393094,-0.932013 +91,1,0.983247,1.2419,11.1387,2.78883,0.398346,-0.93214 +92,1,0.98312,1.25007,11.1429,2.78693,0.395806,-0.93125 +93,1,0.983469,1.25334,11.156,2.78592,0.392436,-0.932013 +94,1,0.983846,1.24594,11.1558,2.78891,0.397314,-0.932672 +95,1,0.983032,1.23872,11.1478,2.78719,0.394868,-0.931916 +96,1,0.983294,1.24409,11.1415,2.78792,0.398291,-0.93131 +97,1,0.983862,1.25252,11.1504,2.78657,0.392919,-0.932475 +98,1,0.982987,1.24922,11.1508,2.78636,0.395376,-0.931896 +99,1,0.983335,1.24249,11.1493,2.78929,0.397018,-0.932138 +100,1,0.984137,1.24299,11.1477,2.78831,0.396008,-0.932537 +101,1,0.983529,1.25066,11.1476,2.78821,0.395668,-0.932215 +102,1,0.983128,1.25102,11.1509,2.78732,0.396194,-0.932082 +103,1,0.983293,1.24356,11.1492,2.78892,0.396995,-0.932029 +104,1,0.983602,1.24118,11.1509,2.78879,0.394662,-0.93263 +105,1,0.983485,1.24556,11.1443,2.78886,0.398045,-0.932685 +106,1,0.983617,1.25209,11.1493,2.78762,0.395138,-0.932994 +107,1,0.983774,1.25104,11.1579,2.78611,0.392466,-0.932901 +108,1,0.983804,1.23938,11.1548,2.78838,0.394305,-0.932798 +109,1,0.983459,1.24344,11.1415,2.7892,0.398208,-0.932081 +110,1,0.984077,1.25233,11.1483,2.7885,0.394776,-0.931779 +111,1,0.983409,1.24964,11.1542,2.78658,0.393797,-0.932477 +112,1,0.983428,1.24413,11.149,2.78646,0.394806,-0.931906 +113,1,0.983808,1.24159,11.1423,2.78834,0.397259,-0.932581 +114,1,0.983084,1.24566,11.1425,2.78803,0.395986,-0.931205 +115,1,0.98253,1.24961,11.1447,2.78819,0.395792,-0.932122 +116,1,0.983647,1.24508,11.1516,2.78703,0.394482,-0.932563 +117,1,0.98323,1.24575,11.1495,2.78973,0.39656,-0.932434 +118,1,0.983099,1.24572,11.1493,2.7874,0.396166,-0.932402 +119,1,0.982982,1.24424,11.1396,2.78764,0.397477,-0.931826 +120,1,0.982761,1.24579,11.1411,2.78983,0.398468,-0.932857 +121,1,0.983218,1.24202,11.1446,2.78648,0.395809,-0.931486 +122,1,0.983266,1.24514,11.1433,2.79032,0.397768,-0.931829 +123,1,0.98287,1.24485,11.1383,2.78705,0.397578,-0.931888 +124,1,0.983192,1.2448,11.1465,2.78768,0.395832,-0.931648 +125,1,0.983005,1.24638,11.1391,2.78897,0.397687,-0.932204 +126,1,0.983545,1.244,11.1487,2.78631,0.395131,-0.931829 +127,1,0.98309,1.24368,11.1447,2.78688,0.394325,-0.932706 +128,1,0.983628,1.24548,11.152,2.78802,0.395567,-0.931453 +129,1,0.982487,1.24372,11.1378,2.78884,0.398569,-0.932319 +130,1,0.98383,1.24799,11.1446,2.78597,0.394799,-0.932138 +131,1,0.983176,1.24757,11.1422,2.78803,0.397179,-0.932092 +132,1,0.983006,1.24422,11.1437,2.78825,0.397364,-0.932195 +133,1,0.984229,1.24223,11.1575,2.78623,0.3929,-0.932006 +134,1,0.982894,1.24389,11.1422,2.787,0.397098,-0.931214 +135,1,0.983367,1.252,11.1537,2.78737,0.393851,-0.933091 +136,1,0.983872,1.24787,11.1513,2.78689,0.395922,-0.932762 +137,1,0.982977,1.24347,11.1438,2.78774,0.396223,-0.931996 +138,1,0.983269,1.2403,11.1506,2.7877,0.393342,-0.932859 +139,1,0.983277,1.24166,11.1421,2.787,0.396695,-0.932075 +140,1,0.982814,1.24864,11.1415,2.78649,0.396156,-0.932221 +141,1,0.982575,1.24793,11.1422,2.78769,0.396501,-0.931781 +142,1,0.982739,1.24634,11.1421,2.78811,0.397551,-0.93196 +143,1,0.983285,1.24243,11.149,2.78841,0.396701,-0.932346 +144,1,0.983129,1.24051,11.1462,2.78825,0.39444,-0.932423 +145,1,0.982753,1.24458,11.1429,2.78746,0.395539,-0.931988 +146,1,0.982925,1.24797,11.1462,2.78689,0.395303,-0.933423 +147,1,0.983077,1.24764,11.1479,2.78648,0.396027,-0.93263 +148,1,0.983347,1.24433,11.1488,2.78487,0.394214,-0.931793 +149,1,0.982665,1.24171,11.1449,2.78775,0.396471,-0.93192 +150,1,0.983108,1.24275,11.1477,2.7885,0.395324,-0.932423 +151,1,0.98252,1.24455,11.1438,2.78765,0.396324,-0.931686 +152,1,0.982835,1.247,11.1459,2.78761,0.395629,-0.932211 +153,1,0.98286,1.24501,11.1413,2.78786,0.398924,-0.93148 +154,1,0.982919,1.24388,11.1502,2.78692,0.394977,-0.931694 +155,1,0.983349,1.24326,11.1525,2.78711,0.394503,-0.931942 +156,1,0.982427,1.24317,11.1402,2.78842,0.397435,-0.932383 +156,21,-17.0059,11.8637,34.2484,1.97364,-0.546658,-0.391881 +157,1,0.982363,1.24539,11.1419,2.78761,0.397423,-0.931928 +158,1,0.982617,1.24601,11.1448,2.78562,0.395345,-0.931505 +159,1,0.983023,1.24448,11.1479,2.78721,0.395495,-0.932204 +160,1,0.983311,1.24382,11.1502,2.7873,0.395175,-0.931935 +161,1,0.982415,1.24366,11.1425,2.78662,0.395982,-0.932072 +162,1,0.982967,1.24568,11.1448,2.78889,0.398267,-0.931734 +163,1,0.982564,1.24451,11.1362,2.78911,0.399854,-0.931964 +164,1,0.983249,1.24746,11.1442,2.78752,0.397037,-0.93259 +165,1,0.982771,1.24468,11.142,2.78836,0.398068,-0.931805 +166,1,0.981978,1.24372,11.1426,2.78806,0.396436,-0.931621 +167,1,0.983196,1.24338,11.1489,2.78603,0.395044,-0.931823 +168,1,0.983158,1.24398,11.1461,2.78676,0.395613,-0.931272 +169,1,0.982477,1.2466,11.1405,2.78839,0.398326,-0.931567 +170,1,0.983631,1.25161,11.1508,2.78722,0.394901,-0.932601 +171,1,0.982313,1.24783,11.1466,2.78713,0.394676,-0.931934 +172,1,0.982414,1.24543,11.1447,2.78973,0.397415,-0.932368 +173,1,0.982089,1.24168,11.1444,2.78788,0.396856,-0.93224 +174,1,0.982497,1.24427,11.1465,2.78742,0.395554,-0.932034 +175,1,0.982221,1.24991,11.1446,2.78873,0.395902,-0.932764 +176,1,0.98251,1.24939,11.1454,2.78904,0.395824,-0.933347 +177,1,0.983053,1.24731,11.1494,2.78998,0.397015,-0.932234 +178,1,0.983712,1.2434,11.1552,2.78746,0.394321,-0.931944 +179,1,0.983346,1.24104,11.1481,2.78872,0.396452,-0.931615 +180,1,0.982414,1.24609,11.1404,2.78735,0.396914,-0.931869 +181,1,0.982474,1.24891,11.1415,2.78889,0.395034,-0.932509 +182,1,0.983038,1.2487,11.141,2.78759,0.394244,-0.932734 +183,1,0.982613,1.24465,11.141,2.78968,0.39863,-0.932918 +184,1,0.982389,1.24183,11.1381,2.78807,0.398161,-0.932096 +185,1,0.982693,1.24397,11.1432,2.78635,0.396073,-0.93143 +186,1,0.982759,1.24687,11.1435,2.78588,0.395982,-0.93148 +187,1,0.982186,1.24851,11.1404,2.78678,0.394664,-0.931995 +188,1,0.982603,1.24715,11.1474,2.7878,0.396603,-0.932957 +189,1,0.982931,1.24507,11.1497,2.78864,0.395974,-0.931409 +190,1,0.982748,1.24369,11.1483,2.7855,0.393877,-0.931413 +191,1,0.982931,1.24505,11.1446,2.78889,0.396689,-0.932362 +192,1,0.982905,1.24884,11.1511,2.78801,0.39312,-0.933519 +193,1,0.982263,1.24855,11.1432,2.7894,0.396542,-0.933153 +194,1,0.982841,1.24614,11.1505,2.78921,0.396687,-0.932091 +195,1,0.982571,1.24429,11.1472,2.78764,0.395608,-0.931924 +196,1,0.982109,1.24439,11.1421,2.78681,0.396372,-0.931661 +197,1,0.98268,1.24705,11.145,2.78748,0.39709,-0.932013 +198,1,0.983134,1.24877,11.1479,2.78646,0.394038,-0.931577 +199,1,0.983009,1.24713,11.1448,2.78706,0.396696,-0.932031 +200,1,0.9834,1.24441,11.1477,2.78642,0.395161,-0.931503 +201,1,0.983375,1.24158,11.1534,2.78742,0.394969,-0.931334 +202,1,0.982475,1.24825,11.1495,2.78738,0.395281,-0.931706 +203,1,0.982371,1.25172,11.1512,2.78609,0.393265,-0.931976 +204,1,0.982023,1.24656,11.1454,2.78871,0.397002,-0.931481 +205,1,0.982423,1.24477,11.1489,2.78671,0.394915,-0.931926 +206,1,0.982838,1.24168,11.1533,2.78779,0.393707,-0.931696 +207,1,0.98184,1.24421,11.1414,2.78828,0.39633,-0.932587 +208,1,0.981546,1.24658,11.1402,2.7875,0.39668,-0.931535 +209,1,0.98239,1.24884,11.1487,2.78799,0.395417,-0.93173 +210,1,0.982455,1.2462,11.15,2.7871,0.395343,-0.931558 +211,1,0.982613,1.24202,11.1515,2.78806,0.393631,-0.931709 +212,1,0.982313,1.24341,11.147,2.78705,0.394834,-0.932201 +213,1,0.982265,1.24467,11.1462,2.78874,0.396237,-0.931394 +214,1,0.981703,1.24696,11.1417,2.78951,0.397429,-0.931466 +215,1,0.981644,1.24668,11.1433,2.79022,0.398123,-0.932607 +216,1,0.982129,1.24475,11.1457,2.78742,0.396094,-0.931495 +217,1,0.98195,1.24377,11.149,2.7862,0.393623,-0.93197 +218,1,0.982343,1.24422,11.1444,2.78829,0.396771,-0.932047 +219,1,0.981827,1.24657,11.1445,2.78871,0.39689,-0.932723 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_april.txt new file mode 100644 index 0000000..88d223d --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_april.txt @@ -0,0 +1,219 @@ +iter,id,x,y,z,r,p,y +0,1,15.8893,-1.14342,-2.75015,1.03666,0.549423,-0.12755 +1,1,15.8927,-1.1434,-2.74878,1.03544,0.548057,-0.128592 +2,1,15.8966,-1.14412,-2.75193,1.04026,0.54824,-0.139608 +3,1,15.8808,-1.14254,-2.74893,1.03798,0.549791,-0.133802 +4,1,15.8928,-1.14327,-2.75071,1.03915,0.549156,-0.135457 +5,1,15.8739,-1.14183,-2.74558,1.0358,0.549403,-0.126981 +6,1,15.8742,-1.14323,-2.74709,1.03694,0.550304,-0.12833 +7,1,15.8896,-1.1438,-2.75021,1.03879,0.546894,-0.135582 +8,1,15.8941,-1.14434,-2.75105,1.03796,0.549932,-0.133289 +9,1,15.9017,-1.14466,-2.7503,1.0383,0.547399,-0.131392 +10,1,15.9031,-1.14474,-2.75268,1.03746,0.548284,-0.134162 +11,1,15.8907,-1.14407,-2.75121,1.03799,0.55019,-0.130557 +12,1,15.8933,-1.14387,-2.75116,1.03812,0.547982,-0.132707 +13,1,15.8799,-1.14306,-2.74724,1.03865,0.549747,-0.136228 +14,1,15.8909,-1.14396,-2.74997,1.03706,0.549555,-0.129595 +15,1,15.8859,-1.14309,-2.74979,1.03953,0.548896,-0.133868 +16,1,15.8977,-1.14391,-2.75195,1.04023,0.547385,-0.138451 +17,1,15.8887,-1.14357,-2.74934,1.03569,0.549114,-0.12907 +18,1,15.8963,-1.14427,-2.75057,1.03636,0.547109,-0.127316 +19,1,15.8908,-1.14363,-2.751,1.03718,0.546253,-0.127009 +20,1,15.8917,-1.14367,-2.75012,1.03969,0.549713,-0.136293 +21,1,15.9008,-1.14481,-2.75124,1.03794,0.548788,-0.130091 +22,1,15.8781,-1.14278,-2.74782,1.03699,0.551399,-0.131648 +23,1,15.8855,-1.14335,-2.74977,1.03824,0.548868,-0.127606 +24,1,15.9021,-1.14506,-2.75272,1.03861,0.548583,-0.129668 +25,1,15.8947,-1.14345,-2.75086,1.03833,0.546195,-0.134083 +26,1,15.8987,-1.14464,-2.75075,1.03937,0.548708,-0.135065 +27,1,15.8902,-1.14378,-2.7494,1.03742,0.548387,-0.131379 +28,1,15.8958,-1.14338,-2.75119,1.03761,0.545289,-0.131578 +29,1,15.8964,-1.14429,-2.75108,1.03926,0.547016,-0.134303 +30,1,15.8945,-1.14314,-2.74994,1.03905,0.548166,-0.136193 +31,1,15.8953,-1.14441,-2.75112,1.03822,0.547117,-0.133303 +32,1,15.8855,-1.14376,-2.75022,1.03632,0.550271,-0.124638 +33,1,15.8855,-1.14351,-2.7487,1.03576,0.547574,-0.12788 +34,1,15.8914,-1.14376,-2.74943,1.03753,0.550083,-0.129967 +35,1,15.8877,-1.14368,-2.74936,1.03647,0.549024,-0.1315 +36,1,15.8941,-1.14386,-2.75108,1.03813,0.546245,-0.132906 +37,1,15.8942,-1.1445,-2.7507,1.03837,0.54955,-0.131028 +38,1,15.906,-1.14483,-2.75243,1.0377,0.546836,-0.135745 +39,1,15.8767,-1.14193,-2.74826,1.03696,0.549797,-0.129585 +40,1,15.8965,-1.14428,-2.7516,1.03939,0.5478,-0.135144 +41,1,15.895,-1.14446,-2.75167,1.03658,0.548322,-0.128109 +42,1,15.8998,-1.14377,-2.75149,1.03389,0.547867,-0.124353 +43,1,15.8849,-1.14253,-2.74937,1.03855,0.547757,-0.132398 +44,1,15.8955,-1.14377,-2.75107,1.03996,0.546955,-0.13472 +45,1,15.886,-1.14395,-2.74966,1.03767,0.550507,-0.131665 +46,1,15.9002,-1.14408,-2.75186,1.03734,0.546509,-0.131926 +47,1,15.8803,-1.14274,-2.74835,1.03795,0.548295,-0.130958 +48,1,15.8966,-1.14456,-2.75074,1.03846,0.54825,-0.136376 +49,1,15.8822,-1.14322,-2.7484,1.03788,0.550447,-0.132691 +50,1,15.89,-1.14386,-2.75011,1.03798,0.547671,-0.129616 +51,1,15.8828,-1.14247,-2.74852,1.03666,0.551572,-0.130796 +52,1,15.8954,-1.14408,-2.75046,1.03752,0.548156,-0.132136 +53,1,15.9159,-1.14583,-2.755,1.03863,0.547345,-0.137005 +54,1,15.8895,-1.14291,-2.74952,1.03683,0.547441,-0.127947 +55,1,15.8948,-1.14394,-2.75054,1.0385,0.546855,-0.132197 +56,1,15.8844,-1.14288,-2.74847,1.0381,0.54948,-0.134391 +57,1,15.8933,-1.14422,-2.74987,1.03814,0.548289,-0.135325 +58,1,15.8858,-1.14328,-2.74854,1.03882,0.548478,-0.133756 +59,1,15.8922,-1.14364,-2.74953,1.03761,0.548841,-0.132262 +60,1,15.8938,-1.14363,-2.74983,1.03788,0.54953,-0.13112 +61,1,15.8884,-1.14371,-2.74971,1.03519,0.547987,-0.12605 +62,1,15.89,-1.14344,-2.74923,1.03872,0.547481,-0.136595 +63,1,15.9032,-1.14424,-2.75215,1.03526,0.5443,-0.130185 +64,1,15.8876,-1.14317,-2.74975,1.03658,0.548134,-0.128811 +65,1,15.8938,-1.14344,-2.75082,1.0387,0.547702,-0.134241 +66,1,15.8835,-1.14292,-2.7492,1.03822,0.548859,-0.130074 +67,1,15.9014,-1.14412,-2.75229,1.03658,0.54575,-0.131059 +68,1,15.8991,-1.14411,-2.75196,1.0402,0.547171,-0.135687 +69,1,15.8925,-1.14358,-2.75097,1.0387,0.546823,-0.136381 +70,1,15.8827,-1.14259,-2.74916,1.03718,0.548724,-0.129441 +71,1,15.8836,-1.14266,-2.74909,1.03841,0.547919,-0.133123 +72,1,15.8911,-1.1437,-2.7506,1.03928,0.547527,-0.131734 +73,1,15.8785,-1.14265,-2.74816,1.04157,0.550239,-0.141533 +74,1,15.8907,-1.14413,-2.75115,1.03688,0.547769,-0.129123 +75,1,15.8862,-1.14325,-2.7492,1.03748,0.550204,-0.133869 +76,1,15.8886,-1.14286,-2.74959,1.03891,0.547752,-0.138365 +77,1,15.883,-1.14287,-2.74931,1.03833,0.54976,-0.132132 +78,1,15.8899,-1.14315,-2.75032,1.03745,0.548474,-0.132493 +79,1,15.8824,-1.14318,-2.74839,1.04003,0.549391,-0.134315 +80,1,15.8779,-1.14261,-2.74875,1.03921,0.549456,-0.133031 +81,1,15.8967,-1.14437,-2.75058,1.03828,0.547401,-0.135401 +82,1,15.8812,-1.14335,-2.74894,1.03812,0.550114,-0.128709 +83,1,15.8779,-1.14188,-2.74792,1.04081,0.547298,-0.141631 +84,1,15.894,-1.14377,-2.75112,1.03846,0.548664,-0.130594 +85,1,15.8967,-1.14396,-2.75192,1.0411,0.548287,-0.138313 +86,1,15.88,-1.14232,-2.74849,1.03835,0.548813,-0.13119 +87,1,15.8854,-1.14349,-2.75013,1.03894,0.549044,-0.130979 +88,1,15.8984,-1.14418,-2.75203,1.03717,0.54763,-0.128964 +89,1,15.8823,-1.14262,-2.7488,1.03897,0.546831,-0.137589 +90,1,15.8913,-1.1434,-2.75031,1.03951,0.549309,-0.138104 +91,1,15.8825,-1.1427,-2.74938,1.03729,0.54893,-0.130061 +92,1,15.8901,-1.14315,-2.75047,1.03934,0.547752,-0.134311 +93,1,15.8913,-1.14329,-2.75056,1.03769,0.549314,-0.130224 +94,1,15.8837,-1.14269,-2.74944,1.03833,0.547815,-0.131634 +95,1,15.8986,-1.14433,-2.75213,1.03798,0.547625,-0.131679 +96,1,15.8963,-1.14395,-2.75084,1.03819,0.548097,-0.131911 +97,1,15.8872,-1.14294,-2.7496,1.03686,0.545899,-0.129864 +98,1,15.894,-1.14411,-2.75152,1.03546,0.547058,-0.127809 +99,1,15.8865,-1.14332,-2.74937,1.03937,0.549021,-0.135929 +100,1,15.8808,-1.14259,-2.74865,1.03745,0.549526,-0.129501 +101,1,15.8903,-1.14348,-2.75043,1.03696,0.54956,-0.132903 +102,1,15.9066,-1.14473,-2.75334,1.03829,0.545699,-0.130932 +103,1,15.8973,-1.14382,-2.75164,1.03796,0.545256,-0.131763 +104,1,15.8925,-1.14425,-2.75008,1.03745,0.548592,-0.13474 +105,1,15.9002,-1.14361,-2.75071,1.0385,0.548953,-0.135219 +106,1,15.9074,-1.14403,-2.75191,1.03606,0.547266,-0.130386 +107,1,15.8761,-1.1422,-2.74809,1.03833,0.552264,-0.129753 +108,1,15.889,-1.14348,-2.74934,1.03571,0.548086,-0.127906 +109,1,15.8826,-1.14248,-2.74815,1.03736,0.551189,-0.133169 +110,1,15.8914,-1.14341,-2.75019,1.03553,0.547967,-0.128942 +111,1,15.8876,-1.14262,-2.7492,1.03831,0.549913,-0.132773 +112,1,15.9011,-1.14424,-2.75172,1.03602,0.5477,-0.129646 +113,1,15.8803,-1.14211,-2.7477,1.03807,0.547773,-0.13093 +114,1,15.8848,-1.14344,-2.74902,1.03472,0.547729,-0.124246 +115,1,15.8824,-1.14231,-2.74882,1.0353,0.548854,-0.13002 +116,1,15.8814,-1.14291,-2.74887,1.03693,0.546598,-0.126436 +117,1,15.8934,-1.14387,-2.75091,1.03502,0.547461,-0.123937 +118,1,15.8904,-1.14371,-2.74904,1.03642,0.549977,-0.130088 +119,1,15.8844,-1.14336,-2.74852,1.03678,0.548374,-0.132748 +120,1,15.8998,-1.144,-2.75095,1.03865,0.547253,-0.13655 +121,1,15.8806,-1.14303,-2.74842,1.0369,0.550987,-0.126949 +122,1,15.9053,-1.14393,-2.75239,1.03899,0.546665,-0.133513 +123,1,15.8831,-1.143,-2.74893,1.03816,0.549133,-0.130006 +124,1,15.897,-1.14444,-2.7505,1.03701,0.548607,-0.128308 +125,1,15.8983,-1.14389,-2.7514,1.03547,0.547929,-0.128755 +126,1,15.8721,-1.14213,-2.7466,1.03641,0.546144,-0.129519 +127,1,15.8997,-1.14391,-2.75099,1.03924,0.546274,-0.136465 +128,1,15.8894,-1.1436,-2.74956,1.03725,0.547575,-0.12926 +129,1,15.8866,-1.1435,-2.74902,1.03671,0.548256,-0.128942 +130,1,15.8843,-1.14223,-2.74849,1.0361,0.549936,-0.129322 +131,1,15.8905,-1.14299,-2.75005,1.03435,0.548374,-0.124597 +132,1,15.8832,-1.14283,-2.74843,1.03736,0.547766,-0.132575 +133,1,15.8961,-1.14379,-2.75098,1.03864,0.54678,-0.134021 +134,1,15.8829,-1.14371,-2.74923,1.03604,0.548631,-0.124854 +135,1,15.8907,-1.14364,-2.74993,1.03486,0.549384,-0.131039 +136,1,15.9027,-1.1449,-2.75223,1.03713,0.547109,-0.129539 +137,1,15.887,-1.14281,-2.74922,1.03783,0.549537,-0.130114 +138,1,15.8879,-1.14313,-2.74948,1.03703,0.550133,-0.127424 +139,1,15.8811,-1.14256,-2.74923,1.03625,0.549486,-0.128905 +140,1,15.8859,-1.14294,-2.7491,1.0405,0.549004,-0.138466 +141,1,15.8852,-1.1434,-2.74932,1.03655,0.547624,-0.129041 +142,1,15.8777,-1.14149,-2.74737,1.03795,0.548107,-0.133531 +143,1,15.8902,-1.14371,-2.75014,1.03653,0.55141,-0.128762 +144,1,15.8944,-1.14366,-2.7508,1.03723,0.547599,-0.1301 +145,1,15.8842,-1.14274,-2.74908,1.03875,0.546558,-0.133939 +146,1,15.896,-1.14421,-2.75067,1.03465,0.548779,-0.125331 +147,1,15.8921,-1.1432,-2.75032,1.0372,0.548773,-0.130549 +148,1,15.8941,-1.14402,-2.75025,1.03946,0.547712,-0.135216 +149,1,15.89,-1.14374,-2.74995,1.03639,0.549146,-0.126222 +150,1,15.8884,-1.14238,-2.74941,1.03688,0.548938,-0.13357 +151,1,15.8879,-1.14298,-2.74913,1.03897,0.550615,-0.135904 +152,1,15.8852,-1.1428,-2.74967,1.0391,0.549814,-0.132238 +153,1,15.9007,-1.14396,-2.75156,1.03884,0.545718,-0.135128 +154,1,15.9005,-1.1433,-2.75132,1.03956,0.547066,-0.136024 +155,1,15.8816,-1.14281,-2.74885,1.03478,0.550204,-0.121224 +156,1,15.8914,-1.14345,-2.75032,1.03735,0.548191,-0.130181 +157,1,15.8891,-1.14319,-2.75003,1.03734,0.550222,-0.131133 +158,1,15.8944,-1.1437,-2.75058,1.03615,0.547688,-0.132887 +159,1,15.891,-1.14229,-2.75011,1.03871,0.547678,-0.134863 +160,1,15.882,-1.1423,-2.74867,1.03582,0.550896,-0.12723 +161,1,15.8891,-1.14255,-2.74959,1.03615,0.54688,-0.130108 +162,1,15.8921,-1.14311,-2.75025,1.03626,0.550888,-0.127042 +163,1,15.9015,-1.1437,-2.75117,1.03727,0.546767,-0.133777 +164,1,15.9043,-1.14578,-2.75182,1.03615,0.548835,-0.129928 +165,1,15.9045,-1.14474,-2.75191,1.03571,0.548394,-0.131852 +166,1,15.8913,-1.14332,-2.74997,1.03627,0.547339,-0.12818 +167,1,15.8807,-1.14183,-2.74801,1.03484,0.549205,-0.127349 +168,1,15.8872,-1.14352,-2.74917,1.03795,0.550553,-0.129446 +169,1,15.901,-1.14394,-2.75121,1.03865,0.547966,-0.133434 +170,1,15.8815,-1.142,-2.74841,1.03865,0.548553,-0.13145 +171,1,15.8941,-1.14284,-2.7501,1.0363,0.547,-0.129539 +172,1,15.8962,-1.14376,-2.75079,1.03717,0.549594,-0.128808 +173,1,15.8881,-1.14281,-2.74935,1.03752,0.545995,-0.13211 +174,1,15.891,-1.14286,-2.74997,1.03535,0.546678,-0.128051 +175,1,15.8877,-1.14316,-2.74909,1.03609,0.549289,-0.129997 +176,1,15.8939,-1.14304,-2.75049,1.03607,0.546678,-0.129917 +177,1,15.9055,-1.14486,-2.75257,1.03882,0.54514,-0.134532 +178,1,15.8969,-1.14391,-2.75103,1.03608,0.545958,-0.130763 +179,1,15.8874,-1.14214,-2.74919,1.0357,0.548798,-0.12916 +180,1,15.8764,-1.14149,-2.74719,1.03718,0.548483,-0.130231 +181,1,15.8931,-1.14337,-2.74976,1.03856,0.548435,-0.13292 +182,1,15.8926,-1.14367,-2.74972,1.03843,0.547482,-0.130354 +183,1,15.8844,-1.14262,-2.74817,1.03575,0.549321,-0.127446 +184,1,15.8962,-1.14324,-2.75072,1.03696,0.54827,-0.132405 +185,1,15.8974,-1.14354,-2.75158,1.03641,0.544931,-0.129729 +186,1,15.8955,-1.14296,-2.75062,1.03651,0.548162,-0.128709 +187,1,15.8971,-1.14321,-2.7506,1.03629,0.546056,-0.129323 +188,1,15.879,-1.14212,-2.74751,1.03738,0.548711,-0.12987 +189,1,15.8941,-1.14296,-2.75048,1.03663,0.548793,-0.131542 +190,1,15.879,-1.14273,-2.7476,1.03737,0.550617,-0.129845 +191,1,15.8821,-1.14238,-2.74771,1.03799,0.549811,-0.131937 +192,1,15.8871,-1.14269,-2.7491,1.03746,0.548555,-0.130464 +193,1,15.8867,-1.14321,-2.74854,1.03983,0.547892,-0.136758 +194,1,15.8953,-1.14338,-2.75012,1.03868,0.548082,-0.132646 +195,1,15.8868,-1.14287,-2.74887,1.03684,0.547667,-0.128786 +196,1,15.89,-1.1427,-2.74949,1.03503,0.549008,-0.127994 +197,1,15.8939,-1.14301,-2.75039,1.03697,0.54623,-0.13036 +198,1,15.8867,-1.14325,-2.74924,1.03653,0.549373,-0.130516 +199,1,15.8962,-1.14386,-2.75057,1.0369,0.550042,-0.129413 +200,1,15.8844,-1.14277,-2.74886,1.03632,0.55075,-0.132165 +201,1,15.8859,-1.14289,-2.74913,1.03888,0.548275,-0.133817 +202,1,15.8909,-1.14292,-2.74942,1.03729,0.550123,-0.130142 +203,1,15.8951,-1.14347,-2.75019,1.03554,0.549957,-0.131838 +204,1,15.8678,-1.1415,-2.74563,1.03775,0.549814,-0.135351 +205,1,15.8822,-1.1433,-2.74774,1.03692,0.5503,-0.124977 +206,1,15.8964,-1.14368,-2.75049,1.03661,0.546828,-0.130448 +207,1,15.8831,-1.14266,-2.74832,1.0367,0.550632,-0.12932 +208,1,15.8995,-1.14368,-2.75067,1.03595,0.547828,-0.127847 +209,1,15.8943,-1.14307,-2.74983,1.03522,0.549202,-0.128243 +210,1,15.9044,-1.14417,-2.75158,1.04027,0.545891,-0.138343 +211,1,15.884,-1.14266,-2.7484,1.03541,0.549946,-0.132565 +212,1,15.8785,-1.14179,-2.7478,1.03602,0.548663,-0.126739 +213,1,15.8983,-1.14341,-2.75089,1.037,0.547351,-0.12926 +214,1,15.9029,-1.14422,-2.75193,1.03561,0.547162,-0.12818 +215,1,15.8735,-1.14234,-2.74651,1.03618,0.548905,-0.126926 +216,1,15.8897,-1.14292,-2.74968,1.03881,0.549961,-0.135554 +217,1,15.8945,-1.14315,-2.75009,1.0364,0.549055,-0.131076 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_other.txt new file mode 100644 index 0000000..d481247 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/ccw1-6/pose_other.txt @@ -0,0 +1,209 @@ +iter,id,x,y,z,r,p,y +0,1,1.2666,1.95999,13.7957,2.75489,0.358471,-0.92026 +1,1,1.26722,1.95701,13.8018,2.75583,0.35825,-0.921589 +2,1,1.26759,1.95766,13.8052,2.75585,0.357538,-0.921352 +3,1,1.26608,1.95829,13.7908,2.75098,0.359366,-0.919316 +4,1,1.26646,1.96021,13.7947,2.75445,0.359317,-0.919988 +5,1,1.26684,1.9583,13.7995,2.75556,0.359284,-0.921517 +6,1,1.26681,1.95591,13.7975,2.75447,0.357831,-0.920263 +7,1,1.26583,1.957,13.7891,2.7527,0.358846,-0.921643 +8,1,1.26629,1.95968,13.7929,2.75431,0.362532,-0.920594 +9,1,1.26727,1.95954,13.8021,2.75406,0.359516,-0.920707 +10,1,1.2671,1.95726,13.8012,2.75544,0.358161,-0.920062 +11,1,1.26702,1.95781,13.8002,2.75719,0.360497,-0.920512 +12,1,1.26637,1.95903,13.7933,2.75595,0.360654,-0.920189 +13,1,1.2668,1.95972,13.7981,2.7499,0.355728,-0.921413 +14,1,1.26722,1.95747,13.7997,2.75176,0.357997,-0.920398 +15,1,1.26712,1.95748,13.8006,2.75306,0.358143,-0.920573 +16,1,1.26612,1.95785,13.7902,2.75397,0.359255,-0.920613 +17,1,1.26674,1.9594,13.7942,2.75371,0.357985,-0.920822 +18,1,1.26657,1.9565,13.79,2.7531,0.360806,-0.920322 +19,1,1.26687,1.95712,13.7963,2.75568,0.358178,-0.92056 +20,1,1.26707,1.95933,13.8023,2.754,0.356728,-0.921212 +21,1,1.26722,1.96002,13.8012,2.75158,0.357565,-0.920477 +22,1,1.26686,1.95775,13.7956,2.7557,0.360319,-0.921116 +23,1,1.26631,1.95614,13.7907,2.75464,0.359515,-0.920348 +24,1,1.26754,1.95858,13.8005,2.7502,0.356865,-0.920127 +25,1,1.26725,1.95976,13.8006,2.75296,0.358443,-0.920725 +26,1,1.26628,1.95704,13.7888,2.75272,0.360253,-0.920182 +27,1,1.26718,1.9569,13.7971,2.75468,0.359457,-0.920243 +28,1,1.26722,1.95863,13.8026,2.75709,0.358955,-0.921185 +29,1,1.26708,1.9588,13.7964,2.754,0.358402,-0.921141 +30,1,1.26625,1.9572,13.7855,2.75542,0.361166,-0.920672 +31,1,1.26697,1.95726,13.7961,2.75327,0.358039,-0.920563 +32,1,1.26696,1.95822,13.7955,2.75907,0.361902,-0.921124 +33,1,1.26602,1.95724,13.7877,2.75276,0.35979,-0.920918 +34,1,1.26656,1.95782,13.7905,2.75424,0.359603,-0.920716 +35,1,1.26664,1.95752,13.792,2.75464,0.360217,-0.920417 +36,1,1.26732,1.95792,13.7971,2.75347,0.359018,-0.921625 +37,1,1.2668,1.95826,13.7962,2.75363,0.359059,-0.920443 +38,1,1.26802,1.9592,13.8023,2.75418,0.357378,-0.920663 +39,1,1.26722,1.95774,13.7998,2.7528,0.358173,-0.921633 +40,1,1.26609,1.95619,13.7866,2.75281,0.358973,-0.919904 +41,1,1.26734,1.95863,13.7971,2.75557,0.360607,-0.921086 +42,1,1.26662,1.95763,13.7901,2.75432,0.360179,-0.921057 +43,1,1.26722,1.95755,13.7941,2.75269,0.359005,-0.921214 +44,1,1.26744,1.95795,13.797,2.75371,0.357904,-0.92065 +45,1,1.26716,1.9582,13.7961,2.75181,0.358389,-0.921373 +46,1,1.2681,1.95995,13.8051,2.75578,0.358317,-0.921961 +47,1,1.2669,1.95734,13.7921,2.75396,0.360324,-0.920173 +48,1,1.26748,1.95695,13.795,2.75237,0.357781,-0.921471 +49,1,1.268,1.9594,13.8058,2.75482,0.357236,-0.920891 +50,1,1.26774,1.95968,13.8022,2.75144,0.357494,-0.919049 +51,1,1.26675,1.95689,13.7899,2.75299,0.357732,-0.920993 +52,1,1.26727,1.95711,13.7937,2.75357,0.358971,-0.921179 +53,1,1.26772,1.95842,13.8,2.75424,0.357786,-0.921178 +54,1,1.26728,1.95798,13.7945,2.75343,0.359381,-0.921526 +55,1,1.26813,1.95853,13.8004,2.75317,0.356631,-0.920401 +56,1,1.26766,1.95839,13.8001,2.75405,0.359283,-0.921162 +57,1,1.26627,1.95651,13.7863,2.75397,0.360053,-0.922084 +58,1,1.26674,1.95767,13.79,2.75464,0.360293,-0.921532 +59,1,1.26738,1.95824,13.7966,2.75293,0.359082,-0.92107 +60,1,1.26699,1.95721,13.7915,2.75594,0.361924,-0.92036 +61,1,1.26702,1.95719,13.7939,2.7521,0.357533,-0.920638 +62,1,1.26705,1.9574,13.7901,2.75224,0.360128,-0.921186 +63,1,1.26696,1.95759,13.7906,2.75514,0.359976,-0.921606 +64,1,1.26828,1.95869,13.8046,2.751,0.355776,-0.920395 +65,1,1.26763,1.95782,13.7963,2.75372,0.357444,-0.921617 +66,1,1.26769,1.95848,13.7978,2.75218,0.35738,-0.921827 +67,1,1.26729,1.95782,13.795,2.75329,0.357777,-0.920437 +68,1,1.26741,1.95763,13.7952,2.75341,0.358318,-0.920754 +69,1,1.26804,1.959,13.804,2.75302,0.356292,-0.921353 +70,1,1.26747,1.95772,13.7949,2.75053,0.356748,-0.920335 +71,1,1.26686,1.95759,13.7893,2.75302,0.360217,-0.92057 +72,1,1.26786,1.95862,13.8003,2.75447,0.358735,-0.921243 +73,1,1.26758,1.95824,13.7974,2.75144,0.357039,-0.922122 +74,1,1.26768,1.95834,13.7943,2.75526,0.360312,-0.920104 +75,1,1.2678,1.95855,13.7958,2.75461,0.35867,-0.921512 +76,1,1.2678,1.95904,13.8027,2.75251,0.356947,-0.921271 +77,1,1.26805,1.95886,13.7993,2.7541,0.35902,-0.920235 +78,1,1.26757,1.95758,13.7946,2.75333,0.358258,-0.921277 +79,1,1.26771,1.95825,13.7954,2.75461,0.359357,-0.920164 +80,1,1.26717,1.9576,13.7912,2.75226,0.358975,-0.920952 +81,1,1.26786,1.95832,13.7973,2.75231,0.358739,-0.920191 +82,1,1.26769,1.95832,13.7989,2.75256,0.356631,-0.920207 +83,1,1.26721,1.95827,13.796,2.75209,0.357048,-0.920993 +84,1,1.26832,1.95969,13.8032,2.75584,0.358427,-0.920716 +85,1,1.26746,1.95726,13.7929,2.75431,0.359306,-0.921063 +86,1,1.26727,1.95748,13.792,2.75523,0.358586,-0.920889 +87,1,1.26738,1.95793,13.7906,2.7551,0.361016,-0.920839 +88,1,1.26678,1.95765,13.7897,2.75327,0.359838,-0.921168 +89,1,1.26781,1.95763,13.797,2.75349,0.358961,-0.92126 +90,1,1.26738,1.95765,13.7932,2.75245,0.358572,-0.920556 +91,1,1.26745,1.95725,13.7923,2.75376,0.360443,-0.920811 +92,1,1.26816,1.9589,13.8023,2.75213,0.357531,-0.921832 +93,1,1.26793,1.958,13.7981,2.75534,0.359191,-0.920762 +94,1,1.26777,1.95762,13.7958,2.7556,0.360188,-0.92153 +95,1,1.2673,1.9579,13.7948,2.75186,0.35711,-0.921139 +96,1,1.26761,1.95779,13.7947,2.75317,0.359135,-0.921138 +97,1,1.2675,1.95755,13.7945,2.7524,0.358773,-0.92129 +98,1,1.26746,1.95786,13.7958,2.75189,0.359645,-0.920632 +99,1,1.26807,1.95829,13.8017,2.75302,0.35798,-0.920463 +100,1,1.26787,1.95815,13.7999,2.75164,0.357693,-0.920763 +101,1,1.26757,1.95765,13.7944,2.75287,0.357718,-0.921174 +102,1,1.26721,1.95705,13.792,2.75281,0.359346,-0.919946 +103,1,1.26811,1.9588,13.8042,2.75391,0.356816,-0.921656 +104,1,1.26759,1.95762,13.7957,2.75111,0.358751,-0.9215 +105,1,1.26811,1.95816,13.7982,2.75286,0.358705,-0.920394 +106,1,1.26762,1.95719,13.7942,2.75344,0.358748,-0.920339 +107,1,1.26812,1.9583,13.8029,2.75285,0.356063,-0.921777 +108,1,1.26777,1.95795,13.7966,2.75321,0.358185,-0.920691 +109,1,1.26748,1.95736,13.7952,2.75486,0.360226,-0.92043 +110,1,1.26749,1.95713,13.7933,2.75391,0.358811,-0.921546 +111,1,1.26774,1.95796,13.7951,2.75432,0.359396,-0.921286 +112,1,1.26755,1.95716,13.7954,2.7521,0.35745,-0.921125 +113,1,1.26805,1.95788,13.8,2.7535,0.358284,-0.920066 +114,1,1.26802,1.95789,13.7979,2.75135,0.358202,-0.920581 +115,1,1.26805,1.95825,13.8019,2.75372,0.358212,-0.921485 +116,1,1.26819,1.95864,13.8018,2.75397,0.358871,-0.921578 +117,1,1.26811,1.95806,13.8009,2.75207,0.357453,-0.920437 +118,1,1.26782,1.95826,13.7986,2.75431,0.358379,-0.920713 +119,1,1.26842,1.95908,13.8042,2.75127,0.356279,-0.920732 +120,1,1.26736,1.95721,13.7944,2.75113,0.357326,-0.92117 +121,1,1.26762,1.95787,13.7958,2.75154,0.357951,-0.920742 +122,1,1.26795,1.95783,13.7958,2.75576,0.360102,-0.921237 +123,1,1.2684,1.95808,13.8003,2.75381,0.358717,-0.92053 +124,1,1.26799,1.95809,13.7976,2.7539,0.358717,-0.921319 +125,1,1.26763,1.95745,13.7947,2.75388,0.358925,-0.921302 +126,1,1.26837,1.95859,13.8012,2.75408,0.357083,-0.92107 +127,1,1.26721,1.95726,13.7927,2.75395,0.357953,-0.921077 +128,1,1.26791,1.9585,13.801,2.7539,0.356318,-0.921743 +129,1,1.26741,1.95727,13.7902,2.75293,0.359911,-0.920432 +130,1,1.26737,1.95704,13.7908,2.75298,0.360163,-0.92032 +131,1,1.26754,1.95691,13.7928,2.75548,0.359387,-0.920861 +132,1,1.26831,1.95853,13.8008,2.75329,0.356173,-0.920967 +133,1,1.26806,1.95785,13.8014,2.75333,0.356762,-0.921425 +134,1,1.26813,1.95808,13.8001,2.7553,0.359973,-0.920118 +135,1,1.26834,1.9581,13.8,2.75228,0.357185,-0.921421 +136,1,1.26777,1.95711,13.794,2.7535,0.359462,-0.920903 +137,1,1.26815,1.95856,13.8046,2.75254,0.357712,-0.921015 +138,1,1.26803,1.95808,13.8006,2.75226,0.35761,-0.920723 +139,1,1.26725,1.95587,13.7883,2.7562,0.362334,-0.920352 +140,1,1.26753,1.95696,13.7958,2.75459,0.358993,-0.921049 +141,1,1.26799,1.95775,13.7976,2.75515,0.359867,-0.920664 +142,1,1.26742,1.95678,13.7928,2.75203,0.358324,-0.920944 +143,1,1.26818,1.95682,13.7955,2.75419,0.35939,-0.921498 +144,1,1.26743,1.95672,13.7919,2.75443,0.359446,-0.921093 +145,1,1.26801,1.95748,13.7972,2.75382,0.3604,-0.919956 +146,1,1.2675,1.95698,13.7958,2.75496,0.359589,-0.920551 +147,1,1.26836,1.95788,13.8014,2.753,0.356698,-0.92054 +148,1,1.26872,1.95845,13.8071,2.75061,0.355212,-0.921349 +149,1,1.26774,1.95727,13.7982,2.75599,0.360203,-0.921218 +150,1,1.26649,1.95578,13.7832,2.75537,0.361289,-0.920312 +151,1,1.26713,1.95639,13.7888,2.75375,0.359875,-0.920102 +152,1,1.26779,1.95671,13.7971,2.75227,0.357963,-0.920743 +153,1,1.26721,1.95641,13.7889,2.75214,0.359683,-0.919589 +154,1,1.26769,1.9573,13.796,2.75463,0.358939,-0.919732 +155,1,1.26788,1.95713,13.7979,2.75522,0.358613,-0.920902 +156,1,1.26788,1.95786,13.7999,2.7519,0.356331,-0.920934 +157,1,1.26741,1.95674,13.79,2.75334,0.359157,-0.920467 +158,1,1.26842,1.95844,13.8026,2.75394,0.357738,-0.921117 +159,1,1.26769,1.95699,13.794,2.75263,0.3591,-0.919479 +160,1,1.26768,1.95717,13.7943,2.75401,0.358569,-0.921388 +161,1,1.2673,1.95618,13.7897,2.75437,0.359737,-0.920765 +162,1,1.26729,1.95656,13.7912,2.75266,0.357198,-0.921164 +163,1,1.26758,1.95733,13.7964,2.7544,0.35991,-0.920985 +164,1,1.2681,1.95748,13.7986,2.75541,0.359687,-0.921275 +165,1,1.2681,1.95798,13.8015,2.75333,0.35609,-0.920998 +166,1,1.26868,1.95855,13.8037,2.75227,0.356572,-0.921433 +167,1,1.26724,1.9557,13.786,2.75344,0.360204,-0.920165 +168,1,1.26858,1.95815,13.8049,2.75649,0.358053,-0.921887 +169,1,1.26816,1.95772,13.7983,2.75383,0.359132,-0.920649 +169,3,0.777289,0.0599816,1.55263,1.58363,0.0737636,0.155689 +170,1,1.26809,1.95785,13.7998,2.75585,0.359355,-0.920158 +171,1,1.26762,1.95773,13.797,2.75268,0.358477,-0.921556 +172,1,1.26816,1.95666,13.7945,2.75486,0.360178,-0.920641 +173,1,1.26804,1.95766,13.7998,2.75545,0.359838,-0.920814 +174,1,1.26743,1.9566,13.7907,2.75711,0.361997,-0.921493 +175,1,1.2673,1.95709,13.7924,2.75381,0.359642,-0.920268 +176,1,1.26876,1.95794,13.8045,2.75442,0.358941,-0.921118 +177,1,1.26774,1.95707,13.7965,2.7549,0.358676,-0.921692 +178,1,1.26814,1.95718,13.7965,2.7521,0.357614,-0.92088 +179,1,1.26749,1.95665,13.7926,2.75294,0.359634,-0.920905 +180,1,1.26879,1.95853,13.8039,2.75228,0.356462,-0.921064 +181,1,1.26866,1.95785,13.8012,2.75186,0.35702,-0.920574 +182,1,1.26844,1.95798,13.8021,2.75237,0.356764,-0.921543 +183,1,1.26789,1.95705,13.7961,2.75385,0.357959,-0.920695 +184,1,1.26828,1.95813,13.802,2.75411,0.360129,-0.921401 +185,1,1.26828,1.95716,13.7979,2.75479,0.359001,-0.921313 +186,1,1.2683,1.95781,13.8018,2.75388,0.358029,-0.920592 +187,1,1.26734,1.95651,13.7921,2.75464,0.359299,-0.92044 +188,1,1.26803,1.9573,13.7988,2.7533,0.359288,-0.920298 +189,1,1.26774,1.95618,13.791,2.75322,0.360442,-0.919995 +190,1,1.26867,1.95854,13.8092,2.75182,0.355283,-0.921219 +191,1,1.26835,1.95805,13.8028,2.755,0.357349,-0.92134 +192,1,1.26817,1.95788,13.8,2.75507,0.358095,-0.920835 +193,1,1.26814,1.95755,13.7986,2.75432,0.359112,-0.920498 +194,1,1.26789,1.95737,13.7992,2.75292,0.358819,-0.920189 +195,1,1.26815,1.95752,13.7996,2.75338,0.358789,-0.920381 +196,1,1.26851,1.9575,13.8017,2.75315,0.356763,-0.920184 +197,1,1.26825,1.95725,13.7985,2.75274,0.359043,-0.920519 +198,1,1.26906,1.9587,13.8068,2.7565,0.359014,-0.921201 +199,1,1.26803,1.95663,13.7958,2.75629,0.358369,-0.92057 +200,1,1.26789,1.95772,13.7997,2.75346,0.357287,-0.920427 +201,1,1.26956,1.95926,13.8137,2.75319,0.355979,-0.920788 +202,1,1.26767,1.95566,13.7898,2.75296,0.358562,-0.919789 +203,1,1.26791,1.9564,13.7932,2.75641,0.361267,-0.921175 +204,1,1.26766,1.95689,13.7963,2.75293,0.358121,-0.920039 +205,1,1.26857,1.95714,13.7997,2.75185,0.355642,-0.920813 +206,1,1.26818,1.95738,13.8011,2.75274,0.356458,-0.920714 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_april.txt new file mode 100644 index 0000000..16f5053 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_april.txt @@ -0,0 +1,22 @@ +iter,id,x,y,z,r,p,y +24,1,2.43467,-0.126175,-0.155785,0.983049,0.256718,-0.291378 +28,1,2.43429,-0.126095,-0.155357,0.983261,0.256756,-0.291767 +29,1,2.43441,-0.126428,-0.156288,0.982751,0.257468,-0.290302 +46,1,2.43403,-0.126487,-0.155816,0.982674,0.257584,-0.290134 +56,1,2.4343,-0.126463,-0.156255,0.982697,0.257289,-0.290323 +60,1,2.43473,-0.126182,-0.155749,0.983053,0.256551,-0.29155 +73,1,2.43434,-0.12645,-0.156036,0.982815,0.257532,-0.290675 +75,20,32.7916,4.02457,11.4433,2.08522,-1.82706,2.56355 +80,1,2.43466,-0.126169,-0.155761,0.983075,0.256375,-0.291668 +86,1,2.43411,-0.126515,-0.15609,0.982837,0.257866,-0.290236 +99,1,2.43447,-0.126507,-0.156142,0.982827,0.257505,-0.29034 +110,1,2.43458,-0.126259,-0.155807,0.983196,0.257021,-0.291716 +114,1,2.43428,-0.126456,-0.155974,0.98296,0.257613,-0.291154 +120,1,2.43417,-0.126455,-0.15598,0.982894,0.257512,-0.290674 +121,1,2.43419,-0.126548,-0.156035,0.982978,0.257732,-0.290886 +132,1,2.43461,-0.126072,-0.155691,0.982821,0.256063,-0.291442 +133,5,20.5268,9.97422,6.45112,2.37903,-1.13578,2.4644 +147,1,2.43387,-0.126318,-0.156313,0.983114,0.256949,-0.291038 +153,1,2.4345,-0.126431,-0.1562,0.982953,0.257344,-0.290813 +164,20,5.19801,1.07093,1.32197,0.0828229,0.64726,-1.23192 +294,1,2.43452,-0.12627,-0.155549,0.98301,0.256615,-0.290946 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_other.txt new file mode 100644 index 0000000..0ec4b58 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-1/pose_other.txt @@ -0,0 +1,22 @@ +iter,id,x,y,z,r,p,y +24,1,0.125169,0.155637,2.45773,2.76266,0.0457124,-0.936569 +28,1,0.125103,0.155229,2.45731,2.76232,0.045591,-0.936756 +29,1,0.12541,0.156188,2.45738,2.76315,0.0468813,-0.936084 +46,1,0.125482,0.155741,2.45695,2.76321,0.0470544,-0.935997 +56,1,0.125452,0.156165,2.45726,2.76323,0.0467133,-0.936096 +60,1,0.125186,0.155604,2.45779,2.76261,0.045477,-0.936629 +73,1,0.12543,0.155968,2.45725,2.76283,0.0467536,-0.936111 +75,20,-0.327287,-0.944662,1.74513,1.51306,1.26051,-1.63879 +80,1,0.12518,0.155624,2.4577,2.76261,0.0452805,-0.936707 +86,1,0.125495,0.155995,2.45707,2.76298,0.0472633,-0.936043 +99,1,0.12549,0.156049,2.45743,2.7631,0.0469193,-0.936144 +110,1,0.125251,0.155653,2.45765,2.76222,0.0457924,-0.936598 +114,1,0.125436,0.15589,2.45722,2.76239,0.0465653,-0.936204 +120,1,0.12544,0.155889,2.45712,2.76283,0.0467474,-0.936194 +121,1,0.125521,0.155953,2.45713,2.76255,0.0468335,-0.936187 +132,1,0.125096,0.155556,2.45765,2.76295,0.045075,-0.936588 +133,5,-1.6466,-1.07979,2.6279,1.55582,0.69157,-3.03066 +147,1,0.12529,0.156299,2.45667,2.76292,0.0462466,-0.93655 +153,1,0.125409,0.156115,2.45744,2.76282,0.0465638,-0.93629 +164,20,0.0560201,-0.0267591,0.0239774,2.79429,-1.40544,-0.114378 +294,1,0.125284,0.155411,2.45756,2.76305,0.0458776,-0.936599 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_april.txt new file mode 100644 index 0000000..6cd00f8 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_april.txt @@ -0,0 +1,318 @@ +iter,id,x,y,z,r,p,y +0,1,5.33105,-0.38287,-0.579903,0.988552,0.217275,-0.319329 +1,1,5.3359,-0.383443,-0.579954,0.987023,0.213453,-0.313662 +2,1,5.33192,-0.383103,-0.579508,0.988428,0.216182,-0.317344 +3,1,5.33343,-0.382912,-0.579732,0.987733,0.213893,-0.317986 +4,1,5.33115,-0.383269,-0.579319,0.98832,0.216443,-0.316491 +5,1,5.33081,-0.383109,-0.579679,0.988641,0.215486,-0.318498 +6,1,5.33212,-0.383184,-0.579169,0.988211,0.21557,-0.318252 +7,1,5.33038,-0.383375,-0.57912,0.9886,0.21725,-0.317359 +8,1,5.33172,-0.383384,-0.579445,0.988467,0.216194,-0.317347 +9,1,5.33242,-0.38334,-0.579416,0.988136,0.2159,-0.317782 +10,1,5.33155,-0.383312,-0.579383,0.988241,0.215432,-0.316813 +11,1,5.32945,-0.38293,-0.57932,0.988665,0.217261,-0.320056 +12,1,5.33228,-0.38304,-0.579331,0.988139,0.215347,-0.31838 +13,1,5.33241,-0.38312,-0.57914,0.98777,0.214416,-0.316755 +14,1,5.33083,-0.383199,-0.579375,0.988261,0.216737,-0.31807 +15,1,5.33056,-0.383002,-0.579109,0.988589,0.215427,-0.318058 +16,1,5.3317,-0.383058,-0.579453,0.988504,0.215786,-0.31836 +17,1,5.33078,-0.383044,-0.579394,0.988851,0.21635,-0.318969 +18,1,5.33164,-0.383272,-0.579255,0.988252,0.216303,-0.317026 +19,1,5.33154,-0.383287,-0.579159,0.988156,0.215909,-0.317076 +20,1,5.33032,-0.38334,-0.579391,0.988635,0.218014,-0.316747 +21,1,5.33203,-0.383233,-0.5792,0.988146,0.215053,-0.31806 +22,1,5.33142,-0.383314,-0.57952,0.988188,0.216647,-0.317017 +23,1,5.33238,-0.383013,-0.579574,0.988036,0.213884,-0.319669 +24,1,5.33151,-0.383199,-0.579126,0.988247,0.215094,-0.318378 +25,1,5.3332,-0.38334,-0.57951,0.98755,0.214266,-0.31583 +26,1,5.33131,-0.383353,-0.579364,0.988367,0.216646,-0.316762 +27,1,5.33332,-0.383449,-0.579595,0.987682,0.214589,-0.31605 +28,1,5.33176,-0.383294,-0.579366,0.988236,0.215674,-0.316795 +29,1,5.32987,-0.382945,-0.579177,0.988956,0.21805,-0.320435 +30,1,5.33125,-0.383266,-0.57911,0.98842,0.216138,-0.318128 +31,1,5.33236,-0.38325,-0.579334,0.988401,0.214705,-0.317737 +32,1,5.3329,-0.383175,-0.579275,0.987946,0.215063,-0.316735 +33,1,5.33169,-0.383366,-0.579281,0.988039,0.216284,-0.317969 +34,1,5.33173,-0.383229,-0.579186,0.988458,0.216895,-0.317565 +35,1,5.33233,-0.383088,-0.579443,0.988269,0.214993,-0.319485 +36,1,5.3319,-0.383216,-0.579344,0.988374,0.215315,-0.318174 +37,1,5.33425,-0.383305,-0.579456,0.987718,0.212997,-0.316802 +38,1,5.33218,-0.383373,-0.579353,0.988673,0.215896,-0.31744 +39,1,5.33266,-0.383517,-0.579517,0.988243,0.2156,-0.316256 +39,25,21.7368,3.14746,8.04606,2.78121,0.261466,-1.4137 +40,1,5.33204,-0.383455,-0.579398,0.98819,0.215766,-0.316295 +41,1,5.33187,-0.383317,-0.579405,0.988185,0.214563,-0.318486 +42,1,5.33366,-0.38344,-0.579439,0.987982,0.215111,-0.316932 +43,1,5.33226,-0.383111,-0.579326,0.987943,0.215352,-0.319166 +44,1,5.33262,-0.383352,-0.579226,0.987931,0.215425,-0.317652 +45,1,5.33267,-0.383178,-0.579207,0.988024,0.213899,-0.318862 +46,1,5.33221,-0.383281,-0.579493,0.988099,0.214816,-0.317881 +47,1,5.33137,-0.383227,-0.579338,0.987846,0.214405,-0.317431 +48,1,5.33323,-0.38333,-0.579509,0.988035,0.214066,-0.318815 +49,1,5.3316,-0.38312,-0.579116,0.988365,0.215615,-0.318935 +50,1,5.33166,-0.383106,-0.57923,0.988171,0.215741,-0.319756 +51,1,5.33127,-0.383277,-0.579231,0.988505,0.216382,-0.31868 +52,1,5.33192,-0.383218,-0.57936,0.988216,0.214501,-0.317713 +53,1,5.33247,-0.383213,-0.579373,0.988099,0.214881,-0.317846 +54,1,5.33169,-0.38331,-0.579175,0.988472,0.216811,-0.317279 +55,1,5.33231,-0.383289,-0.57922,0.987669,0.214734,-0.317124 +56,1,5.33292,-0.383387,-0.579216,0.988268,0.215303,-0.315983 +57,1,5.33256,-0.383292,-0.579283,0.987799,0.214812,-0.316132 +58,1,5.33167,-0.383313,-0.579138,0.988249,0.216165,-0.316951 +59,1,5.33337,-0.383434,-0.57944,0.987651,0.215016,-0.315434 +60,1,5.33253,-0.383459,-0.579143,0.987945,0.215143,-0.31673 +61,1,5.33068,-0.383223,-0.579092,0.987923,0.215986,-0.316738 +62,1,5.33219,-0.383217,-0.579029,0.987932,0.215263,-0.317784 +63,1,5.3348,-0.383395,-0.579514,0.987268,0.213866,-0.315284 +64,1,5.33231,-0.383368,-0.579146,0.987678,0.214978,-0.315862 +65,1,5.33109,-0.383236,-0.579096,0.988433,0.215985,-0.318369 +66,1,5.33312,-0.383268,-0.579191,0.987772,0.214419,-0.316547 +67,1,5.33258,-0.383388,-0.579304,0.987954,0.214976,-0.316859 +68,1,5.33137,-0.383194,-0.579133,0.988057,0.215824,-0.317207 +69,1,5.33183,-0.383326,-0.579079,0.988332,0.21566,-0.316884 +70,1,5.33299,-0.383249,-0.579367,0.987592,0.214159,-0.316892 +71,1,5.33387,-0.383429,-0.579353,0.987575,0.214631,-0.315353 +72,1,5.33124,-0.383085,-0.579015,0.987862,0.215215,-0.317483 +73,1,5.33208,-0.383162,-0.579064,0.987902,0.21432,-0.318323 +74,1,5.33407,-0.383312,-0.57949,0.987577,0.213142,-0.315878 +75,1,5.33332,-0.383211,-0.579168,0.987964,0.214575,-0.316934 +76,1,5.33104,-0.383208,-0.57905,0.98806,0.215409,-0.317773 +77,1,5.33344,-0.383308,-0.579197,0.987559,0.213544,-0.316656 +78,1,5.33347,-0.383283,-0.579459,0.987733,0.213973,-0.316178 +79,1,5.33346,-0.383359,-0.579413,0.98764,0.214768,-0.315713 +80,1,5.33275,-0.383375,-0.579114,0.988078,0.215004,-0.316935 +81,1,5.33307,-0.383327,-0.579097,0.988133,0.215849,-0.316852 +82,1,5.33304,-0.383369,-0.579246,0.988078,0.214645,-0.317261 +83,1,5.3313,-0.383016,-0.57897,0.988323,0.214713,-0.318951 +83,25,33.9754,11.2462,12.8577,2.88496,2.71536,2.17096 +84,1,5.33305,-0.38329,-0.579142,0.987842,0.214553,-0.316381 +85,1,5.33331,-0.383353,-0.579415,0.987806,0.215567,-0.316192 +86,1,5.33298,-0.38343,-0.579069,0.987946,0.216235,-0.315882 +87,1,5.33299,-0.38317,-0.579008,0.988135,0.214338,-0.317426 +88,1,5.33258,-0.383289,-0.579057,0.987933,0.213914,-0.317587 +89,1,5.33188,-0.383417,-0.579067,0.987897,0.21529,-0.316553 +90,1,5.33412,-0.383366,-0.579212,0.987937,0.214892,-0.316606 +91,1,5.33334,-0.383277,-0.579285,0.987953,0.214291,-0.31657 +92,1,5.33419,-0.383396,-0.579421,0.987671,0.21464,-0.315914 +93,1,5.33369,-0.383418,-0.579325,0.98775,0.214554,-0.31556 +94,1,5.33265,-0.383361,-0.579019,0.987995,0.215335,-0.317044 +95,1,5.3314,-0.383341,-0.57913,0.988372,0.216691,-0.316298 +96,1,5.33098,-0.38323,-0.579,0.988582,0.21583,-0.31763 +97,1,5.33361,-0.383362,-0.579264,0.987607,0.214779,-0.315692 +98,1,5.33126,-0.383079,-0.578769,0.988136,0.21588,-0.318641 +99,1,5.33173,-0.383185,-0.57886,0.988312,0.215632,-0.317781 +100,1,5.33271,-0.383288,-0.579106,0.988253,0.215936,-0.317291 +101,1,5.33172,-0.383219,-0.578813,0.988436,0.215885,-0.318663 +102,1,5.33292,-0.38342,-0.579297,0.987578,0.214992,-0.3153 +103,1,5.33154,-0.383296,-0.579042,0.98792,0.215385,-0.316797 +104,1,5.33351,-0.383446,-0.579512,0.987999,0.214369,-0.316645 +105,1,5.33333,-0.383319,-0.579269,0.987991,0.21459,-0.317178 +106,1,5.33057,-0.383177,-0.578928,0.988333,0.216358,-0.318441 +107,1,5.33268,-0.383339,-0.579136,0.988192,0.214949,-0.317658 +108,1,5.33227,-0.383116,-0.579192,0.988158,0.21476,-0.318962 +109,1,5.33299,-0.383216,-0.579259,0.987574,0.213851,-0.316595 +110,1,5.33338,-0.383383,-0.579344,0.987899,0.215959,-0.31652 +111,1,5.33285,-0.383285,-0.579055,0.988368,0.215572,-0.318334 +112,1,5.33258,-0.383199,-0.579041,0.988097,0.214655,-0.318519 +113,1,5.33224,-0.38339,-0.579156,0.987942,0.214917,-0.317552 +114,1,5.33249,-0.38308,-0.579037,0.988235,0.215249,-0.318701 +115,1,5.33344,-0.383308,-0.579356,0.987966,0.214741,-0.31712 +116,1,5.33369,-0.38334,-0.579229,0.988366,0.215092,-0.317582 +117,1,5.33267,-0.383226,-0.57906,0.988051,0.215535,-0.318521 +118,1,5.33338,-0.383372,-0.579215,0.987959,0.215917,-0.316896 +119,1,5.3331,-0.383158,-0.579385,0.987724,0.214007,-0.318857 +120,1,5.33445,-0.383429,-0.57927,0.987598,0.214285,-0.316815 +121,1,5.33368,-0.383511,-0.579583,0.987717,0.21458,-0.315234 +122,1,5.33461,-0.383254,-0.579502,0.987672,0.212587,-0.316861 +123,1,5.33195,-0.382933,-0.578917,0.988407,0.215926,-0.318486 +124,1,5.33297,-0.383156,-0.579163,0.987822,0.215054,-0.317882 +125,1,5.33226,-0.383464,-0.579168,0.988045,0.21667,-0.315905 +126,1,5.33148,-0.383183,-0.579188,0.988338,0.215641,-0.318805 +127,1,5.33266,-0.383437,-0.579084,0.988077,0.216134,-0.31687 +128,1,5.33222,-0.38331,-0.579165,0.98832,0.216394,-0.318779 +129,1,5.33104,-0.38332,-0.578897,0.988432,0.216037,-0.317668 +130,1,5.33183,-0.383318,-0.5793,0.988287,0.215002,-0.317945 +131,1,5.3329,-0.383248,-0.579015,0.988117,0.216484,-0.317294 +132,1,5.33391,-0.383361,-0.579324,0.987821,0.214263,-0.315648 +133,1,5.33224,-0.383121,-0.578938,0.988102,0.215184,-0.318305 +134,1,5.33244,-0.38325,-0.578885,0.988426,0.215482,-0.31759 +135,1,5.33344,-0.383248,-0.578986,0.987927,0.214345,-0.317716 +136,1,5.33097,-0.383172,-0.578756,0.9884,0.216481,-0.317652 +137,1,5.33178,-0.383113,-0.578827,0.988201,0.215081,-0.318257 +138,1,5.3316,-0.3833,-0.578982,0.988432,0.216132,-0.316857 +139,1,5.33197,-0.383267,-0.579001,0.988419,0.215958,-0.317135 +140,1,5.3326,-0.383393,-0.579048,0.987932,0.21559,-0.315347 +141,1,5.33273,-0.383359,-0.578996,0.987915,0.214498,-0.31671 +142,1,5.3323,-0.383263,-0.578968,0.987792,0.215183,-0.31569 +143,1,5.33197,-0.383298,-0.578982,0.987883,0.215758,-0.316445 +144,1,5.3321,-0.383229,-0.578972,0.987868,0.21574,-0.316246 +145,1,5.332,-0.383173,-0.578927,0.987852,0.214182,-0.315943 +146,1,5.33275,-0.383302,-0.57901,0.98834,0.215407,-0.317299 +147,1,5.33192,-0.383448,-0.578801,0.988341,0.216873,-0.316753 +148,1,5.33226,-0.383131,-0.578876,0.988037,0.215455,-0.317076 +149,1,5.33184,-0.383189,-0.578827,0.988089,0.214571,-0.318016 +150,1,5.3332,-0.383324,-0.57923,0.987663,0.2142,-0.31642 +151,1,5.333,-0.383372,-0.578989,0.988263,0.214852,-0.316697 +152,1,5.33261,-0.38348,-0.579332,0.98786,0.21482,-0.315203 +153,1,5.33139,-0.383051,-0.578845,0.988229,0.214864,-0.318223 +154,1,5.33203,-0.383355,-0.579004,0.988224,0.215818,-0.317434 +155,1,5.33098,-0.383224,-0.57889,0.988438,0.216058,-0.317267 +156,1,5.33108,-0.383076,-0.578851,0.988373,0.215495,-0.319494 +157,1,5.33126,-0.382974,-0.578825,0.98821,0.21502,-0.319715 +158,1,5.33276,-0.383311,-0.579105,0.988136,0.214717,-0.317495 +159,1,5.3321,-0.383376,-0.579038,0.988064,0.214989,-0.317495 +160,1,5.33236,-0.383084,-0.578996,0.987886,0.21528,-0.317143 +161,1,5.33196,-0.383259,-0.57906,0.98845,0.214786,-0.318074 +162,1,5.33142,-0.383142,-0.578816,0.988059,0.215159,-0.318527 +163,1,5.33265,-0.383214,-0.578965,0.987956,0.21601,-0.317773 +164,1,5.33236,-0.38329,-0.578975,0.987998,0.214702,-0.317243 +165,1,5.33286,-0.383321,-0.579272,0.987615,0.213947,-0.317406 +166,1,5.33306,-0.383283,-0.579104,0.987656,0.21401,-0.316126 +167,1,5.33414,-0.383301,-0.579168,0.987867,0.215234,-0.317118 +168,1,5.33281,-0.383276,-0.579028,0.988346,0.215569,-0.316955 +169,1,5.33339,-0.383306,-0.579302,0.987541,0.213734,-0.317215 +170,1,5.3313,-0.383261,-0.579042,0.988175,0.215212,-0.317403 +171,1,5.33235,-0.383256,-0.579121,0.988118,0.214859,-0.317328 +172,1,5.33356,-0.38342,-0.579208,0.987712,0.214513,-0.316022 +173,1,5.33302,-0.383518,-0.57912,0.9879,0.215019,-0.315717 +174,1,5.33166,-0.383291,-0.579023,0.988319,0.215447,-0.3178 +175,1,5.33161,-0.38318,-0.578834,0.988278,0.215354,-0.31782 +176,1,5.33362,-0.383386,-0.579221,0.98791,0.21552,-0.31571 +177,1,5.33121,-0.38332,-0.578848,0.988345,0.216626,-0.317479 +178,1,5.33365,-0.383406,-0.579238,0.987649,0.215044,-0.315835 +179,1,5.33244,-0.383476,-0.579056,0.987777,0.215725,-0.315598 +180,1,5.33061,-0.382961,-0.578801,0.988224,0.215057,-0.320858 +181,1,5.3334,-0.383472,-0.579293,0.987981,0.2144,-0.31568 +182,1,5.33157,-0.383418,-0.579067,0.9882,0.216772,-0.316674 +183,1,5.3329,-0.383313,-0.579128,0.988449,0.215491,-0.316988 +184,1,5.3321,-0.38313,-0.579014,0.988104,0.213895,-0.318332 +185,1,5.33143,-0.383222,-0.578802,0.988164,0.215776,-0.317603 +186,1,5.33252,-0.383349,-0.579086,0.988214,0.214573,-0.317021 +187,1,5.33191,-0.383315,-0.579079,0.988316,0.216187,-0.317825 +188,1,5.33196,-0.383246,-0.579054,0.988234,0.215232,-0.317696 +189,1,5.33131,-0.383239,-0.578849,0.98846,0.217591,-0.318108 +190,1,5.33094,-0.383122,-0.578914,0.988698,0.215629,-0.317524 +191,1,5.33163,-0.383217,-0.57874,0.98873,0.216249,-0.319125 +192,1,5.3317,-0.383221,-0.578929,0.988383,0.216268,-0.317263 +193,1,5.33159,-0.382982,-0.578867,0.988277,0.215435,-0.319526 +194,1,5.33171,-0.383237,-0.578895,0.988602,0.215462,-0.317686 +195,1,5.33155,-0.38334,-0.578913,0.988394,0.216402,-0.31709 +196,1,5.33236,-0.383209,-0.578856,0.988293,0.215463,-0.317643 +197,1,5.33205,-0.38337,-0.578983,0.988076,0.215807,-0.315887 +198,1,5.33115,-0.38312,-0.578854,0.988576,0.215201,-0.318441 +199,1,5.3324,-0.383346,-0.578976,0.987909,0.214903,-0.316053 +200,1,5.33149,-0.383224,-0.578875,0.988231,0.215748,-0.318488 +201,1,5.33243,-0.383221,-0.579074,0.987959,0.215179,-0.316657 +202,1,5.33318,-0.383339,-0.579148,0.987974,0.214733,-0.316036 +203,1,5.33307,-0.383143,-0.578888,0.98797,0.214975,-0.317266 +204,1,5.33226,-0.383247,-0.579097,0.987803,0.214736,-0.316621 +205,1,5.33131,-0.383194,-0.578869,0.988435,0.215915,-0.317721 +206,1,5.33299,-0.383266,-0.579263,0.987721,0.214089,-0.316551 +207,1,5.33273,-0.383113,-0.578908,0.988024,0.215614,-0.318151 +208,1,5.33185,-0.383077,-0.578856,0.987982,0.214677,-0.317783 +209,1,5.3339,-0.383322,-0.579096,0.987645,0.214503,-0.315705 +210,1,5.33292,-0.3833,-0.57908,0.987946,0.214281,-0.316428 +211,1,5.33235,-0.383354,-0.579095,0.98831,0.215492,-0.317047 +212,1,5.33283,-0.383389,-0.579014,0.988172,0.215279,-0.316571 +213,1,5.33333,-0.383446,-0.579331,0.988064,0.215118,-0.315757 +214,1,5.33136,-0.383117,-0.578775,0.988088,0.216185,-0.317767 +215,1,5.33252,-0.38314,-0.579104,0.988093,0.215143,-0.317498 +216,1,5.33239,-0.383139,-0.578985,0.988049,0.214277,-0.317783 +217,1,5.33327,-0.383263,-0.579092,0.988146,0.215096,-0.316651 +218,1,5.33306,-0.383319,-0.579271,0.988113,0.214919,-0.316627 +219,1,5.33228,-0.383164,-0.578874,0.988204,0.215547,-0.317764 +220,1,5.33284,-0.383245,-0.578901,0.988321,0.215524,-0.317358 +221,1,5.33283,-0.383269,-0.579133,0.987959,0.215076,-0.316013 +222,1,5.3341,-0.383341,-0.579194,0.98763,0.215095,-0.314961 +223,1,5.33327,-0.383416,-0.579133,0.987837,0.214796,-0.315882 +224,1,5.3318,-0.383209,-0.578905,0.988246,0.216168,-0.317013 +225,1,5.33325,-0.383269,-0.579148,0.988053,0.2141,-0.317466 +226,1,5.33379,-0.383162,-0.579144,0.988152,0.214782,-0.316206 +227,1,5.33237,-0.383101,-0.578793,0.988177,0.214963,-0.317578 +228,1,5.33292,-0.38298,-0.579053,0.987804,0.214463,-0.317576 +229,1,5.33229,-0.383221,-0.579022,0.988262,0.214754,-0.316896 +230,1,5.33327,-0.383176,-0.579196,0.987996,0.21471,-0.317074 +231,1,5.33337,-0.383269,-0.579158,0.987956,0.214633,-0.315945 +232,1,5.33246,-0.383049,-0.579016,0.988138,0.215141,-0.317216 +233,1,5.33331,-0.38319,-0.578859,0.987844,0.215749,-0.317624 +234,1,5.33227,-0.383169,-0.579093,0.98789,0.215453,-0.31637 +235,1,5.33203,-0.383293,-0.57897,0.988168,0.215496,-0.316488 +236,1,5.33372,-0.383308,-0.579389,0.987426,0.214128,-0.315249 +237,1,5.33276,-0.383406,-0.579183,0.988244,0.215781,-0.316301 +238,1,5.33192,-0.38328,-0.578921,0.988209,0.215473,-0.317204 +239,1,5.33125,-0.383015,-0.578875,0.988067,0.215363,-0.317797 +240,1,5.3333,-0.383154,-0.579025,0.987928,0.21481,-0.316058 +241,1,5.33356,-0.383249,-0.579046,0.987565,0.213726,-0.316354 +242,1,5.33232,-0.383151,-0.578877,0.988342,0.214816,-0.318352 +243,1,5.33237,-0.383327,-0.579046,0.987952,0.215551,-0.316819 +244,1,5.33345,-0.383171,-0.579082,0.987977,0.215277,-0.316429 +245,1,5.33293,-0.383295,-0.579113,0.988099,0.215559,-0.31673 +246,1,5.33248,-0.383203,-0.578835,0.988126,0.214963,-0.317578 +247,1,5.33343,-0.383188,-0.579163,0.987978,0.214864,-0.317056 +248,1,5.33218,-0.38329,-0.578969,0.98807,0.214468,-0.315444 +249,1,5.332,-0.383132,-0.579115,0.988123,0.215214,-0.316221 +250,1,5.33288,-0.383064,-0.579175,0.988043,0.214485,-0.316531 +251,1,5.33349,-0.383131,-0.579069,0.987585,0.214348,-0.315816 +252,1,5.33017,-0.383062,-0.578771,0.988474,0.215895,-0.317909 +253,1,5.33271,-0.383238,-0.579139,0.987889,0.21409,-0.316091 +254,1,5.33209,-0.383038,-0.578961,0.987853,0.214687,-0.317688 +255,1,5.33104,-0.38331,-0.578964,0.988201,0.215946,-0.316946 +256,1,5.3327,-0.383206,-0.57925,0.987814,0.214084,-0.316127 +257,1,5.33298,-0.383286,-0.579106,0.987743,0.214978,-0.315468 +258,1,5.33297,-0.383268,-0.57898,0.987998,0.215331,-0.316185 +259,1,5.33232,-0.383118,-0.578913,0.988071,0.213976,-0.316421 +260,1,5.33289,-0.383151,-0.578938,0.987852,0.214944,-0.317263 +261,1,5.33162,-0.383195,-0.578853,0.988119,0.215513,-0.316375 +262,1,5.33272,-0.383072,-0.578952,0.987493,0.213522,-0.316399 +263,1,5.33208,-0.383286,-0.5789,0.988215,0.215713,-0.315632 +264,1,5.33331,-0.383113,-0.579112,0.987621,0.214258,-0.315854 +265,1,5.3326,-0.383052,-0.578949,0.987997,0.213852,-0.317555 +266,1,5.33154,-0.383131,-0.57884,0.988065,0.215259,-0.316592 +267,1,5.33322,-0.383238,-0.579094,0.98788,0.214575,-0.315607 +268,1,5.33342,-0.383349,-0.579084,0.987845,0.21508,-0.314836 +269,1,5.33299,-0.38313,-0.579063,0.987547,0.214054,-0.315187 +270,1,5.33164,-0.382991,-0.578683,0.987981,0.214869,-0.316706 +271,1,5.33341,-0.383111,-0.579138,0.987507,0.213748,-0.316079 +272,1,5.33087,-0.382878,-0.578797,0.987902,0.214481,-0.316912 +273,1,5.33163,-0.383168,-0.57877,0.987953,0.215035,-0.317177 +274,1,5.33192,-0.38297,-0.578847,0.987692,0.213901,-0.317796 +275,1,5.33483,-0.383247,-0.579409,0.987356,0.213368,-0.314262 +276,1,5.33317,-0.383121,-0.579102,0.987715,0.213897,-0.314505 +277,1,5.3328,-0.383063,-0.579036,0.987442,0.213877,-0.314761 +278,1,5.33252,-0.38312,-0.579065,0.987603,0.214243,-0.315845 +279,1,5.33255,-0.383039,-0.578806,0.987686,0.214574,-0.315956 +280,1,5.33187,-0.383197,-0.579024,0.987747,0.215248,-0.31602 +281,1,5.3318,-0.383108,-0.578892,0.987588,0.215189,-0.315331 +282,1,5.33275,-0.383119,-0.579101,0.987461,0.213755,-0.315691 +283,1,5.33228,-0.383072,-0.578934,0.987615,0.214331,-0.315952 +284,1,5.33237,-0.383052,-0.578959,0.987539,0.21414,-0.31567 +285,1,5.33312,-0.383225,-0.579071,0.987724,0.214428,-0.315515 +286,1,5.33224,-0.383089,-0.578877,0.987652,0.214457,-0.316564 +287,1,5.33298,-0.383,-0.578842,0.987422,0.213415,-0.315646 +288,1,5.3319,-0.38304,-0.578726,0.987788,0.215168,-0.316226 +289,1,5.33327,-0.383121,-0.579113,0.987674,0.213247,-0.315883 +290,1,5.33297,-0.383074,-0.578977,0.987335,0.214099,-0.314892 +291,1,5.33273,-0.38311,-0.579075,0.987707,0.214442,-0.315501 +292,1,5.33236,-0.383281,-0.578715,0.988036,0.215727,-0.315686 +293,1,5.33156,-0.383186,-0.578638,0.988076,0.215559,-0.317518 +294,1,5.33271,-0.383307,-0.578929,0.987677,0.215074,-0.315102 +295,1,5.33234,-0.383233,-0.578925,0.988026,0.216286,-0.315546 +296,1,5.33287,-0.383289,-0.579005,0.987845,0.214921,-0.314124 +297,1,5.33242,-0.383057,-0.57885,0.988078,0.216091,-0.316079 +298,1,5.33227,-0.383261,-0.579015,0.98772,0.214491,-0.314461 +299,1,5.33344,-0.383213,-0.579057,0.987497,0.214627,-0.315124 +300,1,5.3319,-0.383149,-0.578878,0.988138,0.214994,-0.316016 +301,1,5.33086,-0.382903,-0.578758,0.987788,0.214287,-0.31657 +302,1,5.33232,-0.38289,-0.578812,0.988,0.212882,-0.317005 +303,1,5.33396,-0.383044,-0.579123,0.987379,0.213134,-0.314616 +304,1,5.33304,-0.383015,-0.579,0.987438,0.213092,-0.316389 +305,1,5.33205,-0.38326,-0.578786,0.98764,0.215636,-0.315543 +306,1,5.33219,-0.383052,-0.578888,0.987752,0.215131,-0.315395 +307,1,5.33236,-0.383146,-0.578889,0.98773,0.213636,-0.315702 +308,1,5.33142,-0.383208,-0.578956,0.987956,0.215088,-0.316218 +309,1,5.33364,-0.383104,-0.578926,0.987444,0.214359,-0.314483 +310,1,5.33256,-0.383331,-0.579007,0.987636,0.214621,-0.314674 +311,1,5.33332,-0.383167,-0.579186,0.987536,0.214479,-0.313929 +312,1,5.3324,-0.383158,-0.578913,0.987453,0.214912,-0.315024 +313,1,5.3331,-0.383154,-0.579078,0.987323,0.214029,-0.314233 +314,1,5.33323,-0.383153,-0.579132,0.987051,0.212107,-0.314186 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_other.txt new file mode 100644 index 0000000..96951f6 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-2/pose_other.txt @@ -0,0 +1,318 @@ +iter,id,x,y,z,r,p,y +0,1,0.382168,0.580658,5.36757,2.76385,-0.00558896,-0.954028 +1,1,0.38274,0.580775,5.37271,2.77116,-0.00589364,-0.953729 +2,1,0.382398,0.580241,5.36842,2.76597,-0.00531748,-0.954246 +3,1,0.382228,0.580515,5.36996,2.76707,-0.00756618,-0.95428 +4,1,0.382557,0.580109,5.36786,2.76691,-0.00479947,-0.954051 +5,1,0.3824,0.580454,5.36741,2.76568,-0.0065274,-0.954652 +6,1,0.382472,0.57997,5.36881,2.76602,-0.00654506,-0.954219 +7,1,0.382659,0.579911,5.36709,2.76574,-0.0046193,-0.954068 +8,1,0.382668,0.580246,5.36846,2.76641,-0.00548063,-0.954264 +9,1,0.382637,0.580177,5.36898,2.76594,-0.00591839,-0.954055 +10,1,0.382596,0.580181,5.36828,2.76726,-0.00583794,-0.954284 +11,1,0.382218,0.580059,5.36592,2.76315,-0.00603953,-0.954147 +12,1,0.382329,0.580076,5.36878,2.76565,-0.00672563,-0.954235 +13,1,0.382416,0.579934,5.36907,2.76787,-0.00662602,-0.954151 +14,1,0.38247,0.580154,5.36753,2.76535,-0.00564518,-0.953918 +15,1,0.382281,0.579879,5.36719,2.76605,-0.00643016,-0.954623 +16,1,0.382336,0.580218,5.36831,2.76555,-0.00636425,-0.954438 +17,1,0.382321,0.580166,5.36741,2.76478,-0.00617666,-0.954588 +18,1,0.382557,0.579993,5.36818,2.76619,-0.00520064,-0.954047 +19,1,0.382568,0.579963,5.36829,2.76682,-0.00568401,-0.95406 +20,1,0.382605,0.580215,5.36722,2.76602,-0.00387568,-0.953862 +21,1,0.38253,0.57997,5.36859,2.76626,-0.00672267,-0.954321 +22,1,0.382597,0.580366,5.36831,2.76673,-0.00511091,-0.953853 +23,1,0.38232,0.58027,5.36864,2.76509,-0.00840274,-0.954601 +24,1,0.382483,0.579891,5.3681,2.76594,-0.00695124,-0.954408 +25,1,0.382628,0.580268,5.36981,2.76847,-0.00632182,-0.954002 +26,1,0.38263,0.580189,5.36816,2.7668,-0.00492509,-0.954026 +27,1,0.38274,0.580393,5.37004,2.76837,-0.00617896,-0.954016 +28,1,0.382563,0.580192,5.36863,2.76732,-0.0058066,-0.954203 +29,1,0.382219,0.579985,5.36658,2.76285,-0.00575555,-0.95416 +30,1,0.382548,0.579855,5.3678,2.76542,-0.00594252,-0.954255 +31,1,0.382525,0.580142,5.36912,2.76697,-0.00695406,-0.954659 +32,1,0.382463,0.580117,5.36974,2.76784,-0.00619565,-0.954108 +33,1,0.382652,0.580047,5.3683,2.76561,-0.00587076,-0.95385 +34,1,0.38251,0.579984,5.36846,2.76581,-0.00509549,-0.954044 +35,1,0.382391,0.5802,5.3688,2.76503,-0.00748381,-0.954462 +36,1,0.382501,0.580102,5.36847,2.76593,-0.00659847,-0.95446 +37,1,0.38259,0.580221,5.37085,2.76843,-0.00782759,-0.954547 +38,1,0.382654,0.580144,5.36889,2.76643,-0.00569983,-0.95455 +39,1,0.382799,0.580337,5.36948,2.76778,-0.00543453,-0.954228 +39,25,-0.38871,-0.991192,1.80407,1.57324,1.21217,-0.129305 +40,1,0.382744,0.580214,5.36882,2.76763,-0.00527942,-0.954128 +41,1,0.382612,0.580196,5.3685,2.76632,-0.00738164,-0.954503 +42,1,0.382725,0.58023,5.37037,2.7673,-0.00623338,-0.954144 +43,1,0.382393,0.580051,5.36872,2.76487,-0.00728937,-0.954063 +44,1,0.382642,0.580004,5.36924,2.76644,-0.0063596,-0.954005 +45,1,0.382475,0.579976,5.3692,2.76624,-0.00811729,-0.954563 +46,1,0.382574,0.58027,5.36882,2.76658,-0.00686833,-0.954348 +47,1,0.382527,0.580139,5.36803,2.76736,-0.00698131,-0.954226 +48,1,0.382624,0.58025,5.3697,2.76598,-0.00795573,-0.954532 +49,1,0.382415,0.579878,5.36812,2.76516,-0.00672527,-0.954359 +50,1,0.382403,0.579983,5.36814,2.76436,-0.00715595,-0.954147 +51,1,0.382559,0.580035,5.36798,2.76522,-0.00611216,-0.954246 +52,1,0.382517,0.580131,5.36848,2.76686,-0.00690738,-0.954551 +53,1,0.382501,0.58015,5.36909,2.76658,-0.00684095,-0.954329 +54,1,0.382585,0.579963,5.36842,2.76603,-0.00503659,-0.954086 +55,1,0.382583,0.579955,5.36879,2.76698,-0.00658594,-0.95398 +56,1,0.382668,0.579967,5.36954,2.7677,-0.00541121,-0.954361 +57,1,0.382567,0.580066,5.36928,2.76807,-0.00612958,-0.954066 +58,1,0.382594,0.579926,5.36838,2.76667,-0.00536562,-0.954073 +59,1,0.382724,0.58026,5.37018,2.76879,-0.00555235,-0.95385 +60,1,0.382754,0.579935,5.36921,2.76747,-0.00601542,-0.954095 +61,1,0.382507,0.579907,5.36746,2.76713,-0.00549458,-0.953814 +62,1,0.382512,0.5798,5.36877,2.76638,-0.00650562,-0.954057 +63,1,0.382689,0.580283,5.37143,2.76922,-0.00637937,-0.953854 +64,1,0.382658,0.579943,5.36903,2.76831,-0.00578498,-0.953894 +65,1,0.382528,0.579877,5.3677,2.76555,-0.00614447,-0.954303 +66,1,0.382555,0.579915,5.36961,2.76756,-0.00649744,-0.954174 +67,1,0.382679,0.580085,5.36922,2.76737,-0.00622796,-0.954159 +68,1,0.382478,0.579916,5.36804,2.76662,-0.00580607,-0.953999 +69,1,0.382606,0.579854,5.3685,2.76692,-0.00566924,-0.954308 +70,1,0.382548,0.580116,5.36951,2.7676,-0.0068903,-0.954076 +71,1,0.382722,0.580162,5.37063,2.76901,-0.00578057,-0.953897 +72,1,0.382383,0.579825,5.36792,2.76693,-0.00641017,-0.953993 +73,1,0.382451,0.579777,5.36848,2.76608,-0.00752114,-0.954336 +74,1,0.382609,0.580267,5.37069,2.7692,-0.00714347,-0.954359 +75,1,0.382503,0.579949,5.36995,2.76754,-0.00656814,-0.95429 +76,1,0.382508,0.579838,5.36766,2.76643,-0.0063181,-0.954124 +77,1,0.382618,0.57998,5.37002,2.76838,-0.00718472,-0.954218 +78,1,0.382576,0.580263,5.37018,2.76866,-0.00669503,-0.954249 +79,1,0.382646,0.580238,5.37028,2.76874,-0.00593704,-0.953915 +80,1,0.382659,0.579913,5.36948,2.76741,-0.00630089,-0.954263 +81,1,0.382615,0.579876,5.36972,2.76687,-0.00552067,-0.954061 +82,1,0.382671,0.580007,5.36958,2.76709,-0.00654575,-0.954379 +83,1,0.382309,0.579746,5.36786,2.76576,-0.00747326,-0.954592 +83,25,-0.983075,-1.12704,2.20754,1.50193,-2.25064,-1.63247 +84,1,0.382585,0.579957,5.36979,2.76824,-0.00632647,-0.95417 +85,1,0.382639,0.580193,5.36999,2.76757,-0.00549379,-0.953842 +86,1,0.382706,0.579851,5.36971,2.76748,-0.0048423,-0.95377 +87,1,0.382461,0.579772,5.36956,2.76716,-0.00695968,-0.954528 +88,1,0.382587,0.579802,5.36906,2.76714,-0.00735328,-0.954473 +89,1,0.382702,0.579842,5.36854,2.76741,-0.00588423,-0.954013 +90,1,0.382645,0.579982,5.37077,2.76755,-0.00625185,-0.954175 +91,1,0.382562,0.580025,5.36988,2.76772,-0.00658786,-0.954379 +92,1,0.382677,0.580216,5.37094,2.76844,-0.00615404,-0.953993 +93,1,0.382705,0.580137,5.37047,2.76889,-0.0059516,-0.954085 +94,1,0.382643,0.579777,5.36925,2.76686,-0.00608989,-0.954097 +95,1,0.382619,0.579906,5.36811,2.76683,-0.0045512,-0.95403 +96,1,0.382516,0.57977,5.3676,2.76618,-0.00581839,-0.95449 +97,1,0.38266,0.579988,5.37009,2.76807,-0.00569953,-0.953905 +98,1,0.382359,0.579553,5.3679,2.76541,-0.00659881,-0.954061 +99,1,0.382469,0.57961,5.36828,2.76603,-0.00614806,-0.954306 +100,1,0.382581,0.579853,5.36924,2.76624,-0.00556738,-0.954156 +101,1,0.382512,0.579563,5.36823,2.76516,-0.0063453,-0.954345 +102,1,0.382705,0.580076,5.36962,2.76865,-0.00551149,-0.953801 +103,1,0.382586,0.579836,5.36823,2.76728,-0.00591856,-0.953999 +104,1,0.382746,0.580256,5.37002,2.76764,-0.00642633,-0.954392 +105,1,0.382615,0.58003,5.36988,2.76719,-0.00662366,-0.954316 +106,1,0.382458,0.579762,5.36737,2.76564,-0.00610013,-0.954084 +107,1,0.382634,0.579916,5.36929,2.76672,-0.00659815,-0.954391 +108,1,0.382416,0.579965,5.3688,2.76571,-0.00744398,-0.954423 +109,1,0.382507,0.58001,5.36954,2.76802,-0.007037,-0.954155 +110,1,0.382659,0.580156,5.37019,2.7673,-0.00547689,-0.953804 +111,1,0.382569,0.579829,5.36946,2.76576,-0.00653013,-0.954373 +112,1,0.382494,0.579784,5.36905,2.76593,-0.00729138,-0.954406 +113,1,0.382673,0.579935,5.36889,2.76682,-0.00674844,-0.954172 +114,1,0.382371,0.579769,5.36894,2.76536,-0.00690824,-0.954358 +115,1,0.382596,0.580172,5.37019,2.76752,-0.00663528,-0.954235 +116,1,0.382621,0.580025,5.3704,2.7668,-0.00652481,-0.954509 +117,1,0.382522,0.579817,5.36919,2.76553,-0.00665746,-0.954091 +118,1,0.382645,0.580014,5.37014,2.76693,-0.00571543,-0.953878 +119,1,0.382443,0.580157,5.36968,2.7662,-0.00825079,-0.954255 +120,1,0.382709,0.580063,5.37117,2.76788,-0.00698538,-0.954039 +121,1,0.382793,0.580428,5.37059,2.76937,-0.00585082,-0.954038 +122,1,0.382559,0.580239,5.37106,2.76843,-0.00797118,-0.954629 +123,1,0.382217,0.579696,5.36857,2.76548,-0.00632811,-0.954299 +124,1,0.382453,0.579922,5.3695,2.76634,-0.00673396,-0.954021 +125,1,0.38274,0.579934,5.36895,2.7671,-0.00446844,-0.953734 +126,1,0.382464,0.579955,5.36807,2.76528,-0.00677456,-0.954328 +127,1,0.382703,0.579861,5.36938,2.76667,-0.00552538,-0.95393 +128,1,0.382589,0.579962,5.36892,2.76509,-0.00625313,-0.954073 +129,1,0.382602,0.579631,5.36756,2.76578,-0.00572928,-0.954299 +130,1,0.382625,0.580011,5.36819,2.76599,-0.00647361,-0.95448 +131,1,0.382526,0.579773,5.36951,2.766,-0.00535439,-0.953863 +132,1,0.382649,0.580136,5.37068,2.76899,-0.00619519,-0.954239 +133,1,0.38241,0.579628,5.36858,2.76545,-0.00674502,-0.954264 +134,1,0.382531,0.579636,5.36901,2.76628,-0.00613195,-0.954458 +135,1,0.382536,0.579767,5.37007,2.76703,-0.00724614,-0.95433 +136,1,0.38245,0.579536,5.36764,2.76586,-0.00548628,-0.954122 +137,1,0.38239,0.579581,5.36834,2.76597,-0.00694641,-0.954373 +138,1,0.3826,0.579773,5.36825,2.7668,-0.00510121,-0.954246 +139,1,0.38255,0.579798,5.36869,2.7667,-0.00555777,-0.954291 +140,1,0.382676,0.57983,5.36931,2.76829,-0.00496559,-0.953949 +141,1,0.382654,0.579775,5.36935,2.76776,-0.0064819,-0.954266 +142,1,0.382545,0.579795,5.36913,2.76855,-0.00559438,-0.95393 +143,1,0.382593,0.579789,5.36869,2.76746,-0.00541739,-0.953845 +144,1,0.382502,0.579748,5.3688,2.76742,-0.00548252,-0.953851 +145,1,0.382474,0.579696,5.36858,2.76852,-0.00623177,-0.9543 +146,1,0.38259,0.579792,5.3694,2.76677,-0.00603677,-0.954388 +147,1,0.382721,0.579539,5.36851,2.76609,-0.00468703,-0.953958 +148,1,0.382408,0.579638,5.36887,2.7668,-0.00604625,-0.9541 +149,1,0.38249,0.579562,5.36828,2.76635,-0.00699965,-0.954422 +150,1,0.382612,0.579995,5.36981,2.76807,-0.00668298,-0.954127 +151,1,0.382668,0.579751,5.36957,2.76745,-0.00604591,-0.954486 +152,1,0.382777,0.580099,5.36924,2.76874,-0.00535641,-0.954115 +153,1,0.38234,0.579605,5.36793,2.76617,-0.00698288,-0.95446 +154,1,0.382646,0.579792,5.36869,2.76647,-0.00582431,-0.954154 +155,1,0.382505,0.579625,5.36752,2.76611,-0.0054848,-0.954297 +156,1,0.382371,0.579645,5.36768,2.76499,-0.00717413,-0.954396 +157,1,0.382261,0.579562,5.3677,2.76469,-0.00772573,-0.954409 +158,1,0.382594,0.579827,5.36924,2.76659,-0.00672582,-0.954428 +159,1,0.382667,0.579801,5.36868,2.76672,-0.00652431,-0.954264 +160,1,0.382362,0.579791,5.36907,2.76706,-0.00631672,-0.954004 +161,1,0.382545,0.579805,5.36848,2.76622,-0.00689529,-0.954695 +162,1,0.382443,0.579549,5.36784,2.76557,-0.00685812,-0.954218 +163,1,0.382495,0.57977,5.36937,2.7662,-0.00608903,-0.953845 +164,1,0.382579,0.579683,5.36877,2.76672,-0.00655749,-0.954305 +165,1,0.382611,0.580024,5.3694,2.7673,-0.00742837,-0.954167 +166,1,0.382566,0.579839,5.36959,2.76821,-0.00666276,-0.954187 +167,1,0.382583,0.579949,5.3708,2.76701,-0.00629133,-0.954004 +168,1,0.38255,0.579822,5.36955,2.76704,-0.00585661,-0.954345 +169,1,0.382601,0.580077,5.36998,2.76774,-0.0074977,-0.954154 +170,1,0.382546,0.579816,5.36794,2.76674,-0.006332,-0.954299 +171,1,0.382548,0.579928,5.36905,2.76723,-0.00655539,-0.954341 +172,1,0.382708,0.580055,5.37042,2.76878,-0.00629531,-0.954053 +173,1,0.382815,0.579867,5.36957,2.76807,-0.00545622,-0.954099 +174,1,0.382569,0.57976,5.36819,2.76602,-0.00633192,-0.954375 +175,1,0.382465,0.579593,5.36818,2.76622,-0.00639959,-0.954357 +176,1,0.382664,0.580036,5.37044,2.76824,-0.00532992,-0.953944 +177,1,0.382602,0.579584,5.36775,2.76563,-0.00520413,-0.954037 +178,1,0.382696,0.580041,5.37039,2.76834,-0.0057436,-0.953845 +179,1,0.382768,0.579821,5.36907,2.76789,-0.00496277,-0.953766 +180,1,0.382266,0.579553,5.36701,2.76383,-0.00821367,-0.954408 +181,1,0.382762,0.580082,5.3701,2.76873,-0.00599975,-0.954353 +182,1,0.382687,0.579829,5.36825,2.76637,-0.00483589,-0.953853 +183,1,0.382588,0.579898,5.36957,2.7669,-0.00585481,-0.954471 +184,1,0.382438,0.579771,5.36856,2.76661,-0.00766607,-0.954635 +185,1,0.382518,0.579523,5.36786,2.76591,-0.00584271,-0.954128 +186,1,0.382634,0.579855,5.36914,2.76738,-0.00657777,-0.954529 +187,1,0.382602,0.579833,5.36847,2.7657,-0.00573343,-0.95414 +188,1,0.382531,0.57981,5.36853,2.76637,-0.00643072,-0.954353 +189,1,0.382521,0.579617,5.36794,2.76478,-0.00482968,-0.953842 +190,1,0.382407,0.579663,5.36749,2.76624,-0.0058418,-0.954664 +191,1,0.3825,0.579507,5.36821,2.76468,-0.00633289,-0.954507 +192,1,0.382498,0.579704,5.36837,2.76627,-0.0054353,-0.954172 +193,1,0.382284,0.57965,5.36812,2.76492,-0.00719556,-0.954327 +194,1,0.382522,0.579601,5.36813,2.7659,-0.00604918,-0.954639 +195,1,0.382618,0.579657,5.36813,2.76613,-0.00517319,-0.954148 +196,1,0.382497,0.579645,5.36901,2.76651,-0.00621855,-0.954327 +197,1,0.382662,0.579761,5.36871,2.76769,-0.00497703,-0.954017 +198,1,0.382418,0.579582,5.36757,2.76558,-0.00660163,-0.954687 +199,1,0.382634,0.579713,5.36893,2.76779,-0.005798,-0.954149 +200,1,0.382515,0.579656,5.36809,2.76559,-0.00647236,-0.954188 +201,1,0.382508,0.579848,5.36906,2.76738,-0.00598018,-0.954104 +202,1,0.382626,0.579899,5.36976,2.76799,-0.00592899,-0.954258 +203,1,0.382424,0.579712,5.36985,2.76733,-0.00660382,-0.954166 +204,1,0.38253,0.579842,5.36883,2.76746,-0.00635714,-0.954103 +205,1,0.38248,0.579647,5.36795,2.76611,-0.00587811,-0.954326 +206,1,0.382557,0.579985,5.36946,2.76773,-0.00673829,-0.954227 +207,1,0.3824,0.579685,5.36934,2.76592,-0.00648967,-0.954037 +208,1,0.382373,0.579608,5.36835,2.76659,-0.00688533,-0.954286 +209,1,0.382599,0.579824,5.37045,2.76824,-0.00608982,-0.954029 +210,1,0.382592,0.57986,5.36956,2.76812,-0.00650016,-0.954361 +211,1,0.382649,0.579816,5.3688,2.76652,-0.00569773,-0.954349 +212,1,0.382684,0.579797,5.36947,2.76746,-0.00571531,-0.954266 +213,1,0.382726,0.580143,5.37014,2.76841,-0.00558747,-0.95421 +214,1,0.382398,0.579553,5.368,2.76592,-0.00586548,-0.953922 +215,1,0.382425,0.579903,5.36922,2.76688,-0.0065014,-0.954237 +216,1,0.38244,0.579742,5.36889,2.76685,-0.00713621,-0.954467 +217,1,0.382552,0.579914,5.37005,2.76776,-0.00601434,-0.954289 +218,1,0.382609,0.580043,5.36968,2.76753,-0.00607666,-0.954326 +219,1,0.382446,0.579623,5.36884,2.76608,-0.0062611,-0.954233 +220,1,0.382523,0.579668,5.36947,2.76655,-0.00605895,-0.954343 +221,1,0.382553,0.579928,5.36955,2.76811,-0.00574715,-0.954129 +222,1,0.382617,0.580036,5.37101,2.76929,-0.00537223,-0.953803 +223,1,0.382705,0.579928,5.36999,2.76838,-0.00588518,-0.954098 +224,1,0.382502,0.579613,5.36822,2.76608,-0.00518476,-0.954087 +225,1,0.382566,0.579921,5.36982,2.76731,-0.0071455,-0.954521 +226,1,0.382437,0.579949,5.37056,2.76818,-0.00609776,-0.954398 +227,1,0.382384,0.579597,5.36908,2.76695,-0.00666825,-0.954368 +228,1,0.382282,0.579851,5.36954,2.7672,-0.00701158,-0.95417 +229,1,0.382505,0.579753,5.3688,2.76713,-0.00630351,-0.954529 +230,1,0.382475,0.579979,5.36988,2.76736,-0.00646697,-0.954277 +231,1,0.38255,0.579974,5.37016,2.76856,-0.00609982,-0.954255 +232,1,0.382338,0.57979,5.36907,2.76694,-0.00624405,-0.954284 +233,1,0.382483,0.579637,5.36992,2.7663,-0.00609439,-0.953824 +234,1,0.38246,0.579847,5.36885,2.76734,-0.00556934,-0.95396 +235,1,0.382582,0.5797,5.36853,2.76705,-0.00548792,-0.954212 +236,1,0.3826,0.580199,5.37048,2.76939,-0.00617403,-0.95391 +237,1,0.382703,0.579936,5.36932,2.76719,-0.00509388,-0.954188 +238,1,0.382567,0.579707,5.36858,2.76684,-0.00599162,-0.954246 +239,1,0.38231,0.579638,5.36779,2.76627,-0.00636539,-0.954153 +240,1,0.382433,0.579802,5.36997,2.7681,-0.00599712,-0.954187 +241,1,0.382546,0.579844,5.37023,2.76863,-0.00699673,-0.954167 +242,1,0.382445,0.579648,5.36888,2.76617,-0.0070302,-0.954576 +243,1,0.382612,0.579819,5.36902,2.76703,-0.00581286,-0.953986 +244,1,0.382458,0.579826,5.37,2.76731,-0.00572153,-0.954098 +245,1,0.382583,0.579899,5.36961,2.76718,-0.00569591,-0.954116 +246,1,0.382482,0.579609,5.36912,2.76674,-0.00668661,-0.954331 +247,1,0.382475,0.579933,5.37005,2.7672,-0.00644283,-0.95422 +248,1,0.382581,0.579721,5.36877,2.76865,-0.00571431,-0.954423 +249,1,0.382421,0.57991,5.36871,2.76787,-0.00565624,-0.954238 +250,1,0.382363,0.579948,5.36947,2.76788,-0.00629466,-0.954389 +251,1,0.38241,0.579799,5.37003,2.76826,-0.00628161,-0.95402 +252,1,0.38234,0.579603,5.36698,2.76633,-0.0061074,-0.954355 +253,1,0.38254,0.579949,5.36941,2.76871,-0.00642252,-0.954352 +254,1,0.382341,0.579741,5.36865,2.76685,-0.00684367,-0.954152 +255,1,0.382605,0.57973,5.36763,2.76666,-0.00539024,-0.954097 +256,1,0.382507,0.579986,5.36918,2.76819,-0.00638534,-0.954305 +257,1,0.382583,0.579858,5.36955,2.76834,-0.00540557,-0.953963 +258,1,0.382551,0.579736,5.36958,2.76756,-0.0055911,-0.954098 +259,1,0.38242,0.579666,5.36883,2.76812,-0.00655497,-0.954573 +260,1,0.382449,0.579655,5.36929,2.76664,-0.00636999,-0.954089 +261,1,0.382484,0.579589,5.36815,2.76717,-0.0054373,-0.95416 +262,1,0.382363,0.579643,5.36907,2.76798,-0.00710508,-0.954192 +263,1,0.38257,0.579683,5.36878,2.768,-0.00491836,-0.954174 +264,1,0.382408,0.579912,5.37,2.76875,-0.00629634,-0.954056 +265,1,0.382355,0.579701,5.36908,2.76725,-0.00732198,-0.954547 +266,1,0.382426,0.579573,5.36802,2.76712,-0.0057114,-0.954186 +267,1,0.382525,0.579843,5.3698,2.76843,-0.00582447,-0.954216 +268,1,0.382632,0.579907,5.37026,2.76928,-0.00514721,-0.954009 +269,1,0.382442,0.579791,5.36943,2.76894,-0.00584936,-0.954059 +270,1,0.382283,0.579437,5.36818,2.76739,-0.00615207,-0.954222 +271,1,0.382414,0.579878,5.36989,2.76845,-0.00671029,-0.954118 +272,1,0.382181,0.579523,5.36729,2.76726,-0.00645942,-0.95427 +273,1,0.382469,0.579521,5.36813,2.76689,-0.00623364,-0.954145 +274,1,0.382287,0.579591,5.36832,2.76698,-0.00739548,-0.954246 +275,1,0.382547,0.580175,5.37144,2.77035,-0.00607187,-0.95408 +276,1,0.382418,0.5799,5.36988,2.77006,-0.0057451,-0.954247 +277,1,0.382368,0.579806,5.36939,2.76968,-0.00589168,-0.954005 +278,1,0.382415,0.579804,5.36903,2.76835,-0.00623106,-0.954061 +279,1,0.382335,0.579612,5.36925,2.76853,-0.00609152,-0.954019 +280,1,0.382501,0.579758,5.36835,2.76761,-0.00542799,-0.953888 +281,1,0.38241,0.579673,5.36843,2.76854,-0.00520769,-0.953743 +282,1,0.382419,0.579894,5.3694,2.76913,-0.00659318,-0.954058 +283,1,0.382375,0.579669,5.36875,2.76819,-0.00614685,-0.954043 +284,1,0.382359,0.579687,5.3688,2.76849,-0.00609915,-0.954029 +285,1,0.382536,0.57984,5.36968,2.76873,-0.00575872,-0.954102 +286,1,0.382396,0.579619,5.3687,2.76767,-0.00635825,-0.954039 +287,1,0.382303,0.579584,5.36946,2.76902,-0.0067412,-0.954137 +288,1,0.382344,0.579451,5.36833,2.76743,-0.00557311,-0.953953 +289,1,0.382423,0.579835,5.36969,2.76877,-0.00689802,-0.95443 +290,1,0.382376,0.579758,5.36959,2.76952,-0.00587176,-0.953836 +291,1,0.382394,0.579885,5.3695,2.769,-0.00604321,-0.95408 +292,1,0.382573,0.579443,5.36886,2.76757,-0.00486098,-0.954017 +293,1,0.382492,0.579357,5.36794,2.7661,-0.00588972,-0.954108 +294,1,0.382602,0.579691,5.36932,2.76865,-0.00518038,-0.953869 +295,1,0.382518,0.579694,5.369,2.76765,-0.00447635,-0.953829 +296,1,0.382574,0.57977,5.36954,2.76957,-0.00476031,-0.954072 +297,1,0.382358,0.579638,5.36906,2.76745,-0.00479001,-0.953927 +298,1,0.382558,0.579752,5.3688,2.76935,-0.00517473,-0.954089 +299,1,0.382519,0.579841,5.37007,2.76904,-0.00552828,-0.953827 +300,1,0.382439,0.579574,5.3683,2.76749,-0.0055447,-0.954344 +301,1,0.382217,0.579512,5.36732,2.76785,-0.00638338,-0.95421 +302,1,0.38219,0.579474,5.36853,2.76765,-0.00763104,-0.954865 +303,1,0.382348,0.579895,5.37055,2.77023,-0.00640825,-0.954169 +304,1,0.382316,0.579748,5.36953,2.76862,-0.00744441,-0.954253 +305,1,0.382562,0.579518,5.36854,2.76778,-0.00490927,-0.95367 +306,1,0.382339,0.579609,5.36869,2.7681,-0.00528499,-0.953935 +307,1,0.382459,0.579625,5.3688,2.76881,-0.00639627,-0.954355 +308,1,0.382507,0.579679,5.36788,2.76746,-0.00561943,-0.954137 +309,1,0.382405,0.579715,5.37031,2.76976,-0.00542252,-0.953856 +310,1,0.382626,0.579726,5.36904,2.76898,-0.00522341,-0.953978 +311,1,0.382463,0.579896,5.36978,2.76961,-0.00491588,-0.953927 +312,1,0.382447,0.579655,5.36896,2.76868,-0.0053557,-0.953716 +313,1,0.382455,0.579859,5.36975,2.77011,-0.00556447,-0.953844 +314,1,0.382474,0.579851,5.36961,2.77082,-0.00683242,-0.954178 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_april.txt new file mode 100644 index 0000000..d27e847 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_april.txt @@ -0,0 +1,310 @@ +iter,id,x,y,z,r,p,y +0,1,8.06078,-0.316039,-1.18337,1.00214,0.256937,-0.318035 +1,1,8.06385,-0.316284,-1.18452,1.00134,0.252946,-0.315647 +2,1,8.0619,-0.316144,-1.18451,1.00216,0.256756,-0.318973 +3,1,8.06316,-0.315946,-1.18249,1.00137,0.254457,-0.316265 +4,1,8.06379,-0.316177,-1.18356,1.00159,0.255251,-0.317435 +5,1,8.06322,-0.316039,-1.18248,1.0022,0.256372,-0.317748 +6,1,8.06037,-0.316093,-1.1827,1.00237,0.258311,-0.318661 +7,1,8.06448,-0.31624,-1.18315,1.00186,0.256766,-0.315826 +8,1,8.06546,-0.316336,-1.18402,1.00118,0.255384,-0.314528 +9,1,8.06695,-0.315917,-1.18436,1.00114,0.255032,-0.314647 +10,1,8.06336,-0.316234,-1.18284,1.00201,0.255418,-0.318469 +11,1,8.06542,-0.316232,-1.18266,1.00163,0.255303,-0.316206 +12,1,8.0624,-0.316153,-1.18382,1.00192,0.255088,-0.316358 +13,1,8.06197,-0.31586,-1.18295,1.0024,0.256761,-0.318174 +14,1,8.05964,-0.316142,-1.18318,1.00242,0.256705,-0.315815 +15,1,8.06013,-0.315861,-1.18236,1.00203,0.258085,-0.318076 +16,1,8.06044,-0.31579,-1.18216,1.00219,0.256805,-0.318886 +17,1,8.06234,-0.316256,-1.18366,1.00108,0.255051,-0.316871 +18,1,8.0663,-0.316348,-1.18388,1.00157,0.253345,-0.315892 +19,1,8.06448,-0.315989,-1.1832,1.00139,0.254889,-0.316385 +20,1,8.0622,-0.316195,-1.18371,1.00166,0.255095,-0.316477 +21,1,8.06338,-0.315944,-1.18326,1.00195,0.255498,-0.317599 +22,1,8.06383,-0.316262,-1.18311,1.00128,0.255282,-0.314804 +23,1,8.06401,-0.316206,-1.18366,1.00091,0.255,-0.313893 +24,1,8.066,-0.316295,-1.18405,1.00123,0.255353,-0.313434 +25,1,8.06394,-0.315825,-1.18356,1.00174,0.255297,-0.315752 +26,1,8.06255,-0.316211,-1.18348,1.00108,0.255496,-0.313295 +27,1,8.06489,-0.316214,-1.18421,1.00098,0.253295,-0.316312 +28,1,8.06498,-0.316188,-1.18316,1.00159,0.255478,-0.315813 +29,1,8.06448,-0.316122,-1.18383,1.00156,0.256159,-0.316712 +30,1,8.06338,-0.316205,-1.18341,1.00138,0.25557,-0.318453 +31,1,8.06161,-0.315824,-1.18312,1.00162,0.254604,-0.317918 +32,1,8.06451,-0.316389,-1.18375,1.00111,0.255409,-0.3147 +33,1,8.06383,-0.316265,-1.18359,1.00173,0.256165,-0.31577 +34,1,8.0642,-0.316064,-1.18343,1.00155,0.252534,-0.317382 +35,1,8.06008,-0.316223,-1.18288,1.00213,0.257517,-0.315216 +36,1,8.06155,-0.3159,-1.18298,1.00166,0.25426,-0.319336 +37,1,8.06388,-0.3162,-1.1834,1.00134,0.25455,-0.316446 +38,1,8.06308,-0.31606,-1.18335,1.00139,0.25629,-0.315084 +39,1,8.06463,-0.316074,-1.18381,1.00108,0.254647,-0.314404 +40,1,8.06207,-0.315882,-1.18277,1.00221,0.256188,-0.319126 +41,1,8.06448,-0.316206,-1.18346,1.0013,0.254854,-0.316489 +42,1,8.06493,-0.316242,-1.1837,1.00106,0.255543,-0.315259 +43,1,8.06277,-0.315993,-1.18318,1.00161,0.254204,-0.318197 +44,1,8.06369,-0.316045,-1.1838,1.00108,0.253984,-0.313155 +45,1,8.06461,-0.316401,-1.18381,1.00157,0.256004,-0.315047 +46,1,8.06214,-0.316076,-1.18311,1.00144,0.256311,-0.317693 +47,1,8.06663,-0.315952,-1.18385,1.0013,0.25288,-0.315071 +48,1,8.06764,-0.316088,-1.18423,1.00045,0.252808,-0.312884 +49,1,8.06535,-0.316133,-1.18373,1.00038,0.253753,-0.315394 +50,1,8.06419,-0.316311,-1.18384,1.00142,0.257198,-0.312534 +51,1,8.06357,-0.316221,-1.18381,1.00105,0.253757,-0.313874 +52,1,8.06293,-0.316051,-1.18335,1.00131,0.255365,-0.314868 +53,1,8.06321,-0.316233,-1.18322,1.00155,0.254792,-0.316946 +54,1,8.06286,-0.316296,-1.18358,1.00164,0.255669,-0.317787 +55,1,8.06417,-0.315985,-1.1835,1.00136,0.254514,-0.31769 +56,1,8.06297,-0.316262,-1.18342,1.00158,0.255892,-0.315194 +57,1,8.06432,-0.316183,-1.1837,1.00109,0.25451,-0.315395 +58,1,8.06242,-0.316072,-1.18328,1.00165,0.255439,-0.316999 +59,1,8.05973,-0.31626,-1.1827,1.00268,0.257672,-0.317517 +60,1,8.06316,-0.316405,-1.18361,1.00178,0.2556,-0.314143 +61,1,8.0628,-0.316069,-1.18311,1.00197,0.257008,-0.317587 +62,1,8.06349,-0.316556,-1.18348,1.00145,0.254424,-0.315588 +63,1,8.06268,-0.31602,-1.18377,1.00162,0.255913,-0.317207 +64,1,8.06539,-0.316196,-1.18375,1.00103,0.253596,-0.315686 +65,1,8.06125,-0.315888,-1.18271,1.00157,0.256474,-0.316714 +66,1,8.06145,-0.315884,-1.183,1.00143,0.254253,-0.319129 +67,1,8.05985,-0.31595,-1.18272,1.00249,0.259483,-0.317703 +67,16,37.8744,7.7676,13.2622,1.34416,-0.47632,-0.883426 +68,1,8.06405,-0.316096,-1.18361,1.00051,0.253896,-0.314595 +69,1,8.06218,-0.316227,-1.1833,1.00151,0.25602,-0.317188 +70,1,8.06171,-0.316233,-1.1832,1.00218,0.256105,-0.317812 +71,1,8.06264,-0.31619,-1.18344,1.00167,0.256924,-0.314387 +72,1,8.05985,-0.316094,-1.18259,1.00253,0.256967,-0.318767 +73,1,8.06413,-0.316236,-1.18355,1.00144,0.25481,-0.31638 +74,1,8.06348,-0.316052,-1.18324,1.00169,0.255024,-0.318509 +75,1,8.06557,-0.316261,-1.18413,1.00093,0.254024,-0.314103 +76,1,8.0634,-0.315911,-1.18337,1.00115,0.254632,-0.318352 +77,1,8.06442,-0.31638,-1.18371,1.00169,0.255928,-0.315443 +78,1,8.06178,-0.315957,-1.18331,1.00197,0.255829,-0.318357 +79,1,8.06094,-0.316168,-1.18337,1.00168,0.25651,-0.318142 +80,1,8.06307,-0.315803,-1.18379,1.00099,0.253354,-0.317198 +81,1,8.06382,-0.316101,-1.18453,1.00079,0.254473,-0.314914 +82,1,8.06229,-0.316644,-1.18162,1.00152,0.254656,-0.317903 +83,1,8.06167,-0.316062,-1.17882,1.00143,0.254545,-0.31779 +84,1,8.06425,-0.316185,-1.18547,1.00079,0.25434,-0.313799 +85,1,8.0622,-0.316009,-1.1869,1.00103,0.254493,-0.318009 +86,1,8.06699,-0.316165,-1.18642,1.00133,0.254524,-0.316918 +87,1,8.06247,-0.316048,-1.18393,1.00104,0.253242,-0.316804 +88,1,8.06276,-0.316526,-1.18362,1.00159,0.255718,-0.315074 +89,1,8.05739,-0.315566,-1.17971,1.00239,0.258297,-0.318203 +90,1,8.06112,-0.316348,-1.18193,1.0019,0.256916,-0.317669 +91,1,8.06359,-0.316093,-1.18512,1.00122,0.25391,-0.317609 +92,1,8.06394,-0.316108,-1.18499,1.00135,0.254443,-0.317898 +93,1,8.06449,-0.316475,-1.18511,1.00146,0.254579,-0.315531 +94,1,8.06353,-0.316207,-1.18339,1.00166,0.25553,-0.317284 +95,1,8.05986,-0.316065,-1.18081,1.00242,0.257631,-0.317408 +96,1,8.06183,-0.31631,-1.18252,1.00135,0.254564,-0.314673 +97,1,8.06276,-0.31601,-1.18396,1.00177,0.255058,-0.31564 +98,1,8.0664,-0.316141,-1.18537,1.00084,0.252576,-0.315608 +99,1,8.06246,-0.315962,-1.18518,1.0014,0.255048,-0.318104 +100,1,8.06365,-0.315928,-1.18432,1.00127,0.253018,-0.319612 +101,1,8.06487,-0.316303,-1.18269,1.00198,0.255984,-0.316454 +102,1,8.05801,-0.316155,-1.18091,1.00232,0.257384,-0.318739 +103,1,8.06252,-0.316263,-1.18331,1.0011,0.254065,-0.31548 +104,1,8.0633,-0.316319,-1.1841,1.00135,0.25627,-0.314564 +105,1,8.06375,-0.316312,-1.18479,1.00122,0.254904,-0.315668 +106,1,8.06346,-0.316251,-1.18464,1.00104,0.255323,-0.317523 +107,1,8.0635,-0.316056,-1.18257,1.00151,0.255953,-0.316686 +108,1,8.05665,-0.315693,-1.18054,1.00242,0.257569,-0.321711 +109,1,8.05979,-0.315889,-1.18269,1.00195,0.256464,-0.317948 +110,1,8.06401,-0.316062,-1.18346,1.00162,0.255425,-0.316064 +111,1,8.06541,-0.316231,-1.18497,1.0006,0.252466,-0.315935 +112,1,8.06401,-0.316068,-1.18483,1.00149,0.254055,-0.317194 +113,1,8.06582,-0.316212,-1.18406,1.00137,0.253136,-0.317043 +114,1,8.06338,-0.31606,-1.18202,1.00126,0.254462,-0.317458 +115,1,8.0664,-0.3162,-1.18299,1.00152,0.253875,-0.315266 +116,1,8.06258,-0.316087,-1.18327,1.0017,0.255969,-0.314326 +117,1,8.06386,-0.31618,-1.18456,1.00143,0.254408,-0.318483 +118,1,8.06232,-0.315856,-1.18442,1.00161,0.254019,-0.317786 +119,1,8.06125,-0.316058,-1.18207,1.00217,0.255579,-0.318738 +120,1,8.06397,-0.316215,-1.18237,1.00117,0.253336,-0.315183 +121,1,8.06207,-0.316211,-1.18244,1.00217,0.255194,-0.318837 +122,1,8.06328,-0.316317,-1.18353,1.00168,0.258325,-0.311816 +123,1,8.0627,-0.31632,-1.184,1.00134,0.255133,-0.316529 +124,1,8.06075,-0.316047,-1.18371,1.00214,0.255719,-0.316748 +125,1,8.06322,-0.316172,-1.18302,1.00177,0.255344,-0.318366 +126,1,8.06203,-0.316204,-1.18241,1.00216,0.25807,-0.318245 +127,1,8.06387,-0.315717,-1.18257,1.00101,0.253455,-0.317768 +128,1,8.06205,-0.316143,-1.18251,1.0018,0.255051,-0.317798 +129,1,8.05965,-0.316418,-1.18343,1.00241,0.258569,-0.314656 +130,1,8.07006,-0.316549,-1.18558,0.999891,0.251098,-0.311101 +131,1,8.06271,-0.316376,-1.1834,1.00187,0.256165,-0.314522 +132,1,8.06691,-0.31655,-1.18355,1.00158,0.255359,-0.31446 +133,1,8.06593,-0.31626,-1.18322,1.0016,0.254929,-0.314755 +134,1,8.06599,-0.316277,-1.18367,1.00131,0.254628,-0.313556 +135,1,8.06213,-0.315813,-1.1833,1.0022,0.256602,-0.318758 +136,1,8.06054,-0.316308,-1.18349,1.00198,0.258029,-0.315004 +137,1,8.06395,-0.315958,-1.18366,1.00107,0.254696,-0.317066 +138,1,8.06136,-0.316093,-1.18263,1.00216,0.256459,-0.318291 +139,1,8.05929,-0.316023,-1.18192,1.00274,0.258798,-0.319225 +140,1,8.06134,-0.316245,-1.1826,1.00193,0.257569,-0.316987 +141,1,8.06366,-0.315971,-1.18354,1.0017,0.254681,-0.317329 +142,1,8.06634,-0.316316,-1.18432,1.00125,0.253071,-0.315461 +143,1,8.06324,-0.316277,-1.18348,1.00239,0.256667,-0.317244 +144,1,8.06477,-0.31612,-1.18352,1.00105,0.254249,-0.314152 +145,1,8.05845,-0.316059,-1.18215,1.00288,0.258513,-0.320372 +146,1,8.06385,-0.316339,-1.18318,1.00142,0.257908,-0.313145 +147,1,8.06472,-0.316119,-1.18337,1.00135,0.255314,-0.315174 +148,1,8.06126,-0.316421,-1.18353,1.00216,0.257844,-0.31564 +149,1,8.06337,-0.316196,-1.18363,1.00119,0.253959,-0.317152 +150,1,8.06221,-0.315922,-1.18338,1.00227,0.257383,-0.315535 +151,1,8.06457,-0.31624,-1.18342,1.00141,0.254461,-0.315371 +152,1,8.06386,-0.316083,-1.18318,1.00163,0.255748,-0.316194 +153,1,8.05892,-0.315954,-1.18244,1.00149,0.257474,-0.317052 +154,1,8.06058,-0.315946,-1.18282,1.0023,0.257778,-0.318311 +155,1,8.06319,-0.316447,-1.18362,1.00174,0.256361,-0.313963 +156,1,8.06345,-0.315963,-1.18342,1.00177,0.255142,-0.316361 +157,1,8.06424,-0.316454,-1.18366,1.00115,0.25599,-0.314068 +158,1,8.06195,-0.316106,-1.18261,1.00251,0.258237,-0.318246 +159,1,8.06339,-0.315986,-1.18274,1.0009,0.253358,-0.318203 +160,1,8.06028,-0.316079,-1.18306,1.00246,0.257901,-0.317475 +161,1,8.06311,-0.316034,-1.18366,1.00166,0.255658,-0.316367 +162,1,8.0604,-0.315922,-1.18332,1.00197,0.256619,-0.31662 +163,1,8.06431,-0.316417,-1.18373,1.00121,0.255844,-0.313666 +164,1,8.06217,-0.316181,-1.18326,1.00202,0.255412,-0.318331 +165,1,8.06105,-0.316195,-1.18299,1.0024,0.257665,-0.316947 +166,1,8.0643,-0.316294,-1.18347,1.00133,0.255118,-0.316591 +167,1,8.06415,-0.316036,-1.18345,1.00069,0.250824,-0.317952 +168,1,8.06174,-0.316283,-1.18356,1.00177,0.255328,-0.318437 +169,1,8.06056,-0.31611,-1.18297,1.00198,0.257718,-0.317494 +170,1,8.06594,-0.316093,-1.18376,1.00094,0.2522,-0.316291 +171,1,8.06137,-0.316143,-1.18283,1.00216,0.257239,-0.317134 +172,1,8.06426,-0.316241,-1.18339,1.00101,0.253264,-0.316238 +173,1,8.06427,-0.316128,-1.1837,1.00076,0.253283,-0.314991 +174,1,8.06467,-0.316462,-1.18391,1.0013,0.25428,-0.31711 +175,1,8.0608,-0.315981,-1.18301,1.00201,0.256918,-0.318462 +176,1,8.06247,-0.316202,-1.18318,1.0018,0.256926,-0.315861 +177,1,8.06218,-0.315864,-1.18286,1.00165,0.255333,-0.320235 +178,1,8.06411,-0.316232,-1.1835,1.00074,0.254416,-0.313396 +179,1,8.06462,-0.316283,-1.18387,1.0018,0.255815,-0.314108 +180,1,8.06075,-0.316344,-1.18317,1.00159,0.257324,-0.316709 +181,1,8.06248,-0.316271,-1.18363,1.00155,0.255811,-0.316205 +182,1,8.06238,-0.31619,-1.1831,1.00226,0.256674,-0.316425 +183,1,8.06428,-0.316208,-1.18351,1.0016,0.255367,-0.317443 +184,1,8.06501,-0.315981,-1.18352,1.00066,0.252901,-0.314338 +185,1,8.06646,-0.31626,-1.18397,1.0009,0.253281,-0.315052 +186,1,8.06509,-0.316083,-1.18373,1.00114,0.254301,-0.315772 +187,1,8.0635,-0.31627,-1.18368,1.00172,0.256039,-0.315861 +188,1,8.06092,-0.315781,-1.18293,1.00146,0.255449,-0.316976 +189,1,8.06816,-0.316323,-1.18416,1.00059,0.252744,-0.314532 +190,1,8.0634,-0.315968,-1.18324,1.00115,0.254132,-0.317455 +191,1,8.06302,-0.316063,-1.18319,1.00196,0.25539,-0.318485 +192,1,8.06292,-0.31602,-1.1833,1.0012,0.254958,-0.315363 +193,1,8.06428,-0.316242,-1.18365,1.00178,0.255589,-0.316154 +194,1,8.0643,-0.316041,-1.18375,1.00165,0.254346,-0.317156 +195,1,8.06633,-0.316224,-1.18385,1.0005,0.252803,-0.314874 +196,1,8.06098,-0.315838,-1.18297,1.00164,0.254622,-0.320005 +197,1,8.0655,-0.316154,-1.18367,1.00156,0.253668,-0.314572 +198,1,8.06185,-0.316129,-1.18334,1.00167,0.256659,-0.314869 +199,1,8.06513,-0.316305,-1.18368,1.00139,0.25463,-0.3166 +200,1,8.06351,-0.316276,-1.18358,1.00128,0.255619,-0.31567 +201,1,8.06438,-0.316538,-1.1837,1.00141,0.255974,-0.31482 +202,1,8.06096,-0.316218,-1.18286,1.00148,0.256783,-0.317175 +203,1,8.06261,-0.316209,-1.18298,1.00202,0.255549,-0.315883 +204,1,8.06055,-0.31629,-1.18309,1.00221,0.258088,-0.316152 +205,1,8.06134,-0.315924,-1.18296,1.00203,0.254798,-0.320211 +206,1,8.06535,-0.316393,-1.18396,1.00102,0.254757,-0.312747 +207,1,8.06485,-0.316249,-1.18379,1.00129,0.255385,-0.313284 +208,1,8.06001,-0.316077,-1.1827,1.00177,0.257176,-0.3165 +209,1,8.06198,-0.316198,-1.18285,1.0018,0.255278,-0.318093 +210,1,8.06467,-0.316399,-1.18339,1.00128,0.25542,-0.316507 +211,1,8.0617,-0.316054,-1.18294,1.00172,0.256265,-0.317611 +212,1,8.06356,-0.316275,-1.18343,1.00135,0.256852,-0.313984 +213,1,8.06049,-0.316166,-1.18306,1.0018,0.256587,-0.317108 +214,1,8.06306,-0.31612,-1.18326,1.00095,0.253719,-0.317121 +215,1,8.06319,-0.316153,-1.18318,1.00123,0.254437,-0.31454 +216,1,8.06396,-0.316372,-1.18347,1.00114,0.254471,-0.314141 +217,1,8.06451,-0.31629,-1.18363,1.00188,0.255441,-0.313857 +218,1,8.06464,-0.31635,-1.18354,1.00157,0.254907,-0.316385 +219,1,8.06527,-0.316353,-1.18384,1.00148,0.254035,-0.3161 +220,1,8.06116,-0.316281,-1.18295,1.00187,0.256465,-0.317182 +221,1,8.06443,-0.316366,-1.18326,1.00137,0.255627,-0.315418 +222,1,8.06309,-0.316147,-1.18317,1.00147,0.256994,-0.314 +223,1,8.06314,-0.316223,-1.18336,1.00163,0.256975,-0.315998 +224,1,8.06532,-0.315874,-1.18352,1.00141,0.252916,-0.315063 +225,1,8.06548,-0.31634,-1.18386,1.00106,0.254635,-0.314751 +226,1,8.0636,-0.316086,-1.18327,1.00137,0.25511,-0.316296 +227,1,8.06636,-0.316353,-1.1839,1.00163,0.254223,-0.315952 +228,1,8.06302,-0.316185,-1.18324,1.0018,0.254119,-0.316734 +229,1,8.0632,-0.316281,-1.18335,1.00136,0.255719,-0.315663 +230,1,8.06064,-0.316182,-1.18282,1.00238,0.257931,-0.316969 +231,1,8.06366,-0.316375,-1.18368,1.00176,0.257753,-0.315469 +232,1,8.06228,-0.315983,-1.18308,1.00232,0.256483,-0.315977 +233,1,8.06008,-0.316128,-1.18269,1.00239,0.257492,-0.317312 +234,1,8.06296,-0.316211,-1.18312,1.0014,0.2558,-0.314872 +235,1,8.05602,-0.316027,-1.18218,1.00247,0.259394,-0.317583 +236,1,8.06218,-0.316176,-1.18309,1.00199,0.256391,-0.318481 +237,1,8.06315,-0.316246,-1.1832,1.00191,0.256167,-0.316652 +238,1,8.06096,-0.316193,-1.18309,1.00208,0.25741,-0.316155 +239,1,8.06244,-0.316193,-1.18316,1.0015,0.256441,-0.314581 +240,1,8.06427,-0.316204,-1.18335,1.0015,0.254669,-0.315968 +241,1,8.0621,-0.315981,-1.1829,1.00235,0.255308,-0.319092 +242,1,8.06542,-0.31642,-1.18355,1.00078,0.252743,-0.314733 +243,1,8.06108,-0.316161,-1.18281,1.00208,0.257129,-0.316328 +244,1,8.06244,-0.316337,-1.18315,1.00145,0.256167,-0.31467 +245,1,8.06135,-0.315869,-1.18273,1.00196,0.256739,-0.319142 +246,1,8.0618,-0.316236,-1.18307,1.00147,0.255138,-0.315292 +247,1,8.06219,-0.316139,-1.18306,1.00168,0.256204,-0.317234 +248,1,8.06184,-0.316066,-1.183,1.00148,0.254906,-0.316076 +249,1,8.06117,-0.3161,-1.18289,1.00209,0.258109,-0.317601 +250,1,8.06116,-0.316293,-1.1831,1.0021,0.257058,-0.316786 +251,1,8.05916,-0.316054,-1.18255,1.00225,0.258097,-0.317505 +252,1,8.06188,-0.316367,-1.183,1.00132,0.256612,-0.314928 +253,1,8.06305,-0.316217,-1.1834,1.00111,0.254687,-0.313517 +254,1,8.06253,-0.316207,-1.18313,1.00195,0.257213,-0.314272 +255,1,8.06617,-0.316354,-1.18394,1.00097,0.252204,-0.315946 +256,1,8.06143,-0.316161,-1.183,1.00188,0.25622,-0.316596 +257,1,8.06252,-0.316254,-1.18333,1.00154,0.255845,-0.314306 +258,1,8.0597,-0.316017,-1.18264,1.002,0.258299,-0.317438 +259,1,8.06323,-0.316113,-1.18344,1.00167,0.254368,-0.316019 +260,1,8.0629,-0.315996,-1.18313,1.00148,0.255418,-0.317492 +261,1,8.06333,-0.316267,-1.18336,1.00156,0.254898,-0.316282 +262,1,8.06326,-0.315995,-1.18337,1.00154,0.254855,-0.315682 +263,1,8.06383,-0.316308,-1.18361,1.0012,0.25411,-0.314975 +264,1,8.06126,-0.315941,-1.18281,1.00199,0.257537,-0.317876 +265,1,8.06159,-0.316541,-1.18285,1.00208,0.257353,-0.31627 +266,1,8.06041,-0.316262,-1.18281,1.00187,0.25808,-0.316413 +267,1,8.06761,-0.316501,-1.18389,1.00122,0.254402,-0.313675 +268,1,8.06521,-0.316393,-1.18361,1.00135,0.255472,-0.315904 +269,1,8.06407,-0.316262,-1.18358,1.00187,0.255107,-0.315778 +270,1,8.06545,-0.316465,-1.18369,1.00108,0.255334,-0.315073 +271,1,8.06123,-0.316038,-1.18298,1.00153,0.25716,-0.316316 +272,1,8.06261,-0.316014,-1.18319,1.00151,0.254988,-0.316528 +273,1,8.06246,-0.315986,-1.18313,1.00175,0.25609,-0.317926 +274,1,8.0638,-0.316279,-1.18345,1.00157,0.25415,-0.316887 +275,1,8.06555,-0.316187,-1.18378,1.00138,0.254022,-0.315944 +276,1,8.06306,-0.316449,-1.18335,1.00192,0.255463,-0.315028 +277,1,8.06009,-0.316043,-1.18261,1.00195,0.256537,-0.318775 +278,1,8.06439,-0.316302,-1.18367,1.00105,0.254587,-0.314638 +279,1,8.06276,-0.315994,-1.18322,1.00121,0.255303,-0.315598 +280,1,8.06496,-0.316508,-1.18378,1.00123,0.255511,-0.312841 +281,1,8.06223,-0.316003,-1.18321,1.00178,0.255771,-0.315275 +282,1,8.06089,-0.316188,-1.18311,1.00265,0.257924,-0.317747 +283,1,8.06313,-0.316055,-1.18326,1.00188,0.254068,-0.319327 +284,1,8.06466,-0.316237,-1.1835,1.00168,0.255894,-0.315959 +285,1,8.06493,-0.316393,-1.18355,1.00138,0.25383,-0.315607 +286,1,8.06382,-0.316464,-1.18334,1.00118,0.25484,-0.314496 +287,1,8.06513,-0.31614,-1.18364,1.00077,0.252264,-0.315069 +288,1,8.06017,-0.316183,-1.18283,1.00246,0.256527,-0.318392 +289,1,8.05872,-0.316228,-1.18243,1.00224,0.25831,-0.318764 +290,1,8.06334,-0.316041,-1.18328,1.0015,0.256155,-0.316412 +291,1,8.05888,-0.316339,-1.1827,1.00226,0.258464,-0.316922 +292,1,8.06312,-0.316214,-1.18334,1.00164,0.256227,-0.314772 +293,1,8.0634,-0.316316,-1.18331,1.00117,0.255831,-0.314253 +294,1,8.06008,-0.31582,-1.18276,1.00219,0.256584,-0.318459 +295,1,8.05943,-0.316263,-1.18273,1.00253,0.258982,-0.317203 +296,1,8.06274,-0.315862,-1.18313,1.00146,0.254713,-0.317069 +297,1,8.05909,-0.316127,-1.18255,1.0023,0.256997,-0.318461 +298,1,8.0612,-0.316138,-1.18296,1.00205,0.257724,-0.317746 +299,1,8.06206,-0.316109,-1.18316,1.002,0.254756,-0.317805 +300,1,8.05825,-0.315854,-1.18234,1.0022,0.258438,-0.316557 +301,1,8.06166,-0.316215,-1.18314,1.00136,0.255551,-0.316097 +302,1,8.06309,-0.316323,-1.18347,1.00181,0.256843,-0.315426 +303,1,8.06264,-0.316332,-1.18332,1.00088,0.25488,-0.314243 +304,1,8.06232,-0.3161,-1.18349,1.00212,0.255054,-0.31735 +305,1,8.06318,-0.316298,-1.18355,1.00152,0.254419,-0.318166 +306,1,8.06323,-0.316218,-1.18343,1.0009,0.254624,-0.316075 +307,1,8.06391,-0.31635,-1.18349,1.0011,0.255901,-0.315293 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_other.txt new file mode 100644 index 0000000..374ec4f --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-3/pose_other.txt @@ -0,0 +1,310 @@ +iter,id,x,y,z,r,p,y +0,1,0.315508,1.18548,8.11061,2.73901,0.0277342,-0.95441 +1,1,0.315769,1.18645,8.11278,2.74232,0.0266262,-0.95494 +2,1,0.315612,1.18662,8.11169,2.73828,0.0270727,-0.954458 +3,1,0.315406,1.18458,8.11288,2.7417,0.0264356,-0.954567 +4,1,0.315642,1.1855,8.11274,2.73956,0.0270868,-0.95442 +5,1,0.315503,1.18455,8.11284,2.73938,0.0275242,-0.954651 +6,1,0.315552,1.18482,8.11024,2.73774,0.0282958,-0.954177 +7,1,0.315728,1.18526,8.11427,2.74091,0.0291229,-0.95423 +8,1,0.315832,1.18615,8.11535,2.74282,0.0286239,-0.954077 +9,1,0.315386,1.18646,8.11681,2.74274,0.0278308,-0.954194 +10,1,0.315705,1.18481,8.11245,2.73886,0.0267575,-0.954722 +11,1,0.315677,1.18467,8.11478,2.74082,0.0272012,-0.954538 +12,1,0.315642,1.18578,8.11143,2.74072,0.0280762,-0.954764 +13,1,0.315282,1.18491,8.11109,2.73808,0.0272702,-0.954748 +14,1,0.315601,1.18526,8.10939,2.74074,0.0288317,-0.954811 +15,1,0.315278,1.1843,8.10915,2.73729,0.0281754,-0.953975 +16,1,0.315249,1.18412,8.10945,2.73765,0.0275028,-0.954446 +17,1,0.315771,1.18574,8.11192,2.74099,0.0275078,-0.953975 +18,1,0.315837,1.18599,8.11612,2.74282,0.0263262,-0.955069 +19,1,0.315458,1.18511,8.11329,2.74051,0.0274893,-0.954364 +20,1,0.315676,1.18572,8.11147,2.74079,0.0275995,-0.954551 +21,1,0.315388,1.18523,8.11252,2.73938,0.0268125,-0.954718 +22,1,0.315747,1.1853,8.11405,2.74295,0.0279956,-0.954236 +23,1,0.315681,1.18577,8.11388,2.74339,0.0282221,-0.954008 +24,1,0.31576,1.18617,8.11598,2.74359,0.0286556,-0.954228 +25,1,0.315278,1.18559,8.11337,2.74125,0.0276343,-0.954637 +26,1,0.315682,1.18557,8.11232,2.74347,0.0290276,-0.954016 +27,1,0.315718,1.18614,8.11372,2.74165,0.0267698,-0.954439 +28,1,0.315643,1.18509,8.11396,2.74069,0.0279766,-0.954408 +29,1,0.315586,1.18594,8.11433,2.74046,0.027577,-0.954176 +30,1,0.315699,1.18544,8.11272,2.73913,0.026884,-0.954072 +31,1,0.315284,1.18495,8.10999,2.73902,0.0265954,-0.95462 +32,1,0.315862,1.18584,8.1143,2.74243,0.0281673,-0.954032 +33,1,0.315691,1.18562,8.11332,2.74063,0.0277569,-0.954402 +34,1,0.315538,1.18546,8.11359,2.74164,0.0248368,-0.955286 +35,1,0.315659,1.18503,8.11022,2.74098,0.0290328,-0.954364 +36,1,0.315367,1.1849,8.11036,2.73855,0.0253639,-0.954751 +37,1,0.315691,1.18536,8.11295,2.74101,0.0273805,-0.954403 +38,1,0.315514,1.18548,8.11312,2.74179,0.028252,-0.95405 +39,1,0.315557,1.18588,8.11426,2.74302,0.0280304,-0.954235 +40,1,0.315366,1.18488,8.11177,2.73859,0.0268757,-0.954656 +41,1,0.315686,1.1855,8.11397,2.74114,0.0271166,-0.954311 +42,1,0.315682,1.1858,8.11479,2.7418,0.0273016,-0.953994 +43,1,0.315493,1.18521,8.11208,2.74013,0.0261895,-0.954725 +44,1,0.315517,1.18585,8.11329,2.74428,0.0280889,-0.9545 +45,1,0.315859,1.18597,8.11477,2.74209,0.028103,-0.954311 +46,1,0.315573,1.18523,8.11191,2.73976,0.0276988,-0.953922 +47,1,0.315421,1.18584,8.11587,2.74306,0.0263924,-0.954998 +48,1,0.31557,1.18641,8.11786,2.7458,0.0268532,-0.954325 +49,1,0.315615,1.18569,8.11439,2.74218,0.0268701,-0.953818 +50,1,0.315757,1.18595,8.11415,2.7431,0.0303533,-0.953864 +51,1,0.315712,1.18585,8.1131,2.74389,0.0278636,-0.95449 +52,1,0.315484,1.18531,8.1121,2.74153,0.0278298,-0.954264 +53,1,0.315696,1.18526,8.11268,2.74071,0.0265801,-0.954585 +54,1,0.31578,1.1856,8.11217,2.7395,0.0273049,-0.954309 +55,1,0.315483,1.18551,8.11339,2.74024,0.0266691,-0.954395 +56,1,0.315738,1.18551,8.11271,2.74177,0.0285252,-0.954295 +57,1,0.315688,1.18583,8.11426,2.74275,0.0275384,-0.954243 +58,1,0.315562,1.1853,8.11175,2.74033,0.0276881,-0.954398 +59,1,0.315721,1.18465,8.10874,2.73819,0.0292078,-0.954643 +60,1,0.31585,1.18552,8.11206,2.74176,0.0290231,-0.9546 +61,1,0.315543,1.18526,8.1128,2.73952,0.0279496,-0.954238 +62,1,0.316074,1.1856,8.11327,2.74258,0.0278129,-0.954567 +63,1,0.315504,1.18584,8.11231,2.74012,0.0276112,-0.954241 +64,1,0.315694,1.18575,8.11463,2.74233,0.0269839,-0.954447 +65,1,0.315342,1.1847,8.11044,2.73964,0.0280697,-0.954059 +66,1,0.315384,1.185,8.11061,2.73925,0.0257209,-0.954508 +67,1,0.315373,1.18476,8.10939,2.73728,0.029416,-0.953964 +67,16,-8.88892,-15.1572,43.6361,2.28363,-0.460844,-1.77892 +68,1,0.31559,1.18571,8.11382,2.74349,0.0272122,-0.953935 +69,1,0.315694,1.18533,8.1116,2.73978,0.0274993,-0.954124 +70,1,0.315694,1.18536,8.1118,2.73986,0.0269077,-0.954753 +71,1,0.315617,1.18548,8.11222,2.74137,0.0290843,-0.95414 +72,1,0.315547,1.1846,8.10919,2.7379,0.0275109,-0.954741 +73,1,0.315721,1.18555,8.11335,2.74101,0.0274621,-0.954434 +74,1,0.315523,1.18525,8.11281,2.73927,0.0261665,-0.954574 +75,1,0.315704,1.18604,8.11453,2.74271,0.0274234,-0.954341 +76,1,0.315423,1.18544,8.11293,2.74003,0.0263215,-0.954143 +77,1,0.315829,1.18571,8.11379,2.74103,0.0282427,-0.954402 +78,1,0.315402,1.18506,8.10977,2.73752,0.0274501,-0.954531 +79,1,0.315654,1.18527,8.10964,2.73819,0.0282104,-0.954018 +80,1,0.315319,1.1859,8.11279,2.74186,0.0259004,-0.954448 +81,1,0.315606,1.18665,8.11364,2.743,0.0277684,-0.953978 +82,1,0.31609,1.18354,8.11116,2.73942,0.0259792,-0.954578 +83,1,0.315548,1.18106,8.11201,2.74136,0.0255923,-0.954557 +84,1,0.315683,1.1875,8.11374,2.74355,0.0284371,-0.954044 +85,1,0.315518,1.18881,8.11095,2.73946,0.0269389,-0.954027 +86,1,0.315675,1.18846,8.11647,2.74103,0.0272114,-0.95437 +87,1,0.315557,1.18602,8.11213,2.74212,0.0259802,-0.954545 +88,1,0.315961,1.18571,8.11259,2.74179,0.0276963,-0.954441 +89,1,0.315042,1.18185,8.10724,2.73833,0.0288123,-0.954178 +90,1,0.3158,1.18372,8.10935,2.73775,0.0285722,-0.95413 +91,1,0.315581,1.18711,8.11282,2.74052,0.0260565,-0.954484 +92,1,0.315577,1.18694,8.11296,2.73969,0.0261497,-0.954449 +93,1,0.315956,1.18729,8.11474,2.7427,0.0270598,-0.954617 +94,1,0.31567,1.18539,8.11279,2.73982,0.0271683,-0.954424 +95,1,0.31551,1.18292,8.1097,2.73908,0.0282468,-0.954507 +96,1,0.315775,1.18463,8.11167,2.743,0.0274349,-0.954553 +97,1,0.315469,1.18601,8.11235,2.74164,0.0275255,-0.954746 +98,1,0.315649,1.18738,8.11571,2.74304,0.0263331,-0.954588 +99,1,0.315445,1.1873,8.11233,2.74007,0.026212,-0.95431 +100,1,0.315426,1.18613,8.11183,2.73857,0.0250702,-0.954689 +101,1,0.315741,1.18465,8.11401,2.73997,0.0277302,-0.954629 +102,1,0.315633,1.18302,8.10776,2.73827,0.0278895,-0.954392 +103,1,0.315752,1.18543,8.11237,2.74277,0.0269248,-0.954419 +104,1,0.315756,1.1862,8.11322,2.74194,0.0283101,-0.954051 +105,1,0.315808,1.1869,8.11358,2.7421,0.0276796,-0.954235 +106,1,0.315714,1.1867,8.11306,2.74,0.0264057,-0.953932 +107,1,0.315491,1.18453,8.11262,2.73978,0.0273651,-0.954204 +108,1,0.315155,1.18249,8.10555,2.73499,0.0266487,-0.954319 +109,1,0.315368,1.18484,8.10976,2.73958,0.0274052,-0.954379 +110,1,0.315536,1.18556,8.11377,2.74137,0.0276272,-0.954458 +111,1,0.315756,1.18701,8.11484,2.74307,0.0261847,-0.954361 +112,1,0.315552,1.18683,8.1133,2.74081,0.0263925,-0.954713 +113,1,0.315674,1.18591,8.11437,2.74066,0.0257971,-0.954897 +114,1,0.315517,1.18384,8.11169,2.73941,0.026588,-0.954351 +115,1,0.315666,1.18501,8.1158,2.74251,0.0269358,-0.954892 +116,1,0.315541,1.18534,8.1123,2.74226,0.0287706,-0.95444 +117,1,0.315675,1.18654,8.11294,2.73947,0.0262074,-0.954473 +118,1,0.315364,1.18638,8.11135,2.74029,0.02667,-0.954756 +119,1,0.315499,1.18402,8.11029,2.73838,0.0262924,-0.95487 +120,1,0.315665,1.18435,8.11316,2.74261,0.0262883,-0.954763 +121,1,0.315696,1.18445,8.11132,2.73895,0.0265762,-0.954922 +122,1,0.315747,1.18563,8.11328,2.74297,0.0314492,-0.953783 +123,1,0.315811,1.18613,8.11263,2.7414,0.027219,-0.954269 +124,1,0.315525,1.18583,8.11063,2.7408,0.0276534,-0.954823 +125,1,0.315649,1.18498,8.11225,2.73896,0.0268042,-0.954514 +126,1,0.315641,1.18437,8.11113,2.73735,0.0283782,-0.954066 +127,1,0.315189,1.18448,8.11265,2.74026,0.0254818,-0.954441 +128,1,0.315595,1.18441,8.11083,2.7392,0.0266715,-0.954685 +129,1,0.315867,1.18558,8.1098,2.74087,0.0305028,-0.954275 +130,1,0.316086,1.18768,8.11982,2.74799,0.027651,-0.954272 +131,1,0.315844,1.18554,8.11275,2.74237,0.0288915,-0.954517 +132,1,0.316001,1.18559,8.11645,2.7423,0.0282113,-0.954518 +133,1,0.315734,1.18529,8.11559,2.74258,0.0280539,-0.954633 +134,1,0.315727,1.18568,8.11542,2.74331,0.0281602,-0.954526 +135,1,0.31529,1.18529,8.11132,2.73809,0.0276617,-0.954498 +136,1,0.315751,1.1855,8.11001,2.74023,0.0300762,-0.954009 +137,1,0.315429,1.18564,8.11315,2.74044,0.0265947,-0.954134 +138,1,0.315531,1.18463,8.11064,2.73841,0.0270208,-0.954603 +139,1,0.315481,1.184,8.10896,2.73686,0.0286021,-0.954328 +140,1,0.315677,1.18468,8.11112,2.73922,0.0281083,-0.954103 +141,1,0.315454,1.18565,8.11345,2.74089,0.0265022,-0.954733 +142,1,0.315802,1.18636,8.1158,2.74293,0.0264322,-0.954858 +143,1,0.315755,1.18546,8.11239,2.73919,0.0286837,-0.954685 +144,1,0.315577,1.18549,8.11397,2.74289,0.0276866,-0.954367 +145,1,0.315519,1.18404,8.10712,2.7352,0.0284855,-0.95445 +146,1,0.315759,1.18532,8.11399,2.74225,0.0299571,-0.953677 +147,1,0.315576,1.18536,8.11399,2.74156,0.0279805,-0.95427 +148,1,0.315856,1.18569,8.11148,2.7405,0.0289731,-0.954279 +149,1,0.315681,1.1857,8.11295,2.74123,0.0260215,-0.954484 +150,1,0.315372,1.1855,8.11216,2.74071,0.0291681,-0.954486 +151,1,0.315687,1.18529,8.11327,2.74129,0.0274456,-0.954586 +152,1,0.31557,1.18524,8.11338,2.74095,0.0281889,-0.954322 +153,1,0.315417,1.18447,8.10833,2.73906,0.0286178,-0.953644 +154,1,0.315407,1.18495,8.11045,2.73834,0.028106,-0.954291 +155,1,0.315874,1.18565,8.11278,2.74201,0.0289038,-0.954398 +156,1,0.315443,1.18547,8.11296,2.74111,0.0275884,-0.954658 +157,1,0.315929,1.18578,8.11415,2.74273,0.0289639,-0.9539 +158,1,0.315532,1.18467,8.1116,2.73771,0.0281203,-0.954386 +159,1,0.315474,1.18464,8.11208,2.73997,0.025462,-0.954324 +160,1,0.31551,1.18511,8.10989,2.73848,0.0284132,-0.954456 +161,1,0.315488,1.1857,8.11264,2.74065,0.0274444,-0.954435 +162,1,0.315398,1.18548,8.11049,2.74058,0.0281999,-0.954391 +163,1,0.315863,1.18576,8.11386,2.7426,0.0288439,-0.954045 +164,1,0.315689,1.18539,8.11202,2.73989,0.02699,-0.954718 +165,1,0.315661,1.18506,8.11067,2.73924,0.0291055,-0.954433 +166,1,0.315765,1.18557,8.11411,2.74115,0.0268903,-0.954292 +167,1,0.315554,1.1852,8.11199,2.74094,0.0247002,-0.954856 +168,1,0.315761,1.18563,8.11135,2.73944,0.0264117,-0.954552 +169,1,0.315584,1.18504,8.11016,2.73881,0.0288253,-0.953998 +170,1,0.315573,1.18566,8.1147,2.7421,0.0255097,-0.954807 +171,1,0.315549,1.18475,8.11037,2.7384,0.0279394,-0.954414 +172,1,0.315747,1.18539,8.11346,2.74212,0.0265499,-0.954503 +173,1,0.315593,1.18568,8.11348,2.74283,0.0264941,-0.954375 +174,1,0.315967,1.18598,8.11426,2.74119,0.0266659,-0.954448 +175,1,0.315452,1.185,8.10997,2.73809,0.0278839,-0.954237 +176,1,0.315668,1.18518,8.11175,2.74018,0.0291451,-0.954124 +177,1,0.31537,1.1849,8.11153,2.73799,0.0259564,-0.954334 +178,1,0.315683,1.18559,8.11392,2.74392,0.027631,-0.954095 +179,1,0.315726,1.1859,8.11416,2.74226,0.0287611,-0.954595 +180,1,0.315804,1.18526,8.11051,2.73969,0.0284772,-0.953824 +181,1,0.315728,1.18555,8.11139,2.74011,0.0280958,-0.954244 +182,1,0.315621,1.18509,8.11169,2.73971,0.0281993,-0.954684 +183,1,0.315688,1.18561,8.11407,2.74038,0.0268614,-0.954421 +184,1,0.315452,1.18548,8.11408,2.74348,0.0267319,-0.954399 +185,1,0.315712,1.18593,8.11559,2.74263,0.0263248,-0.954527 +186,1,0.315543,1.18568,8.11416,2.74149,0.026966,-0.954373 +187,1,0.315721,1.18563,8.11254,2.74034,0.0283484,-0.954359 +188,1,0.315239,1.18499,8.11051,2.74041,0.0268951,-0.954302 +189,1,0.315809,1.1861,8.11715,2.74339,0.0267816,-0.954349 +190,1,0.315448,1.18519,8.11234,2.74028,0.0262949,-0.954348 +191,1,0.315533,1.18512,8.11188,2.73864,0.0268491,-0.954676 +192,1,0.315473,1.18543,8.11293,2.74229,0.0269679,-0.954297 +193,1,0.315721,1.18574,8.114,2.74118,0.0278696,-0.954541 +194,1,0.315509,1.18583,8.114,2.74103,0.0261142,-0.954824 +195,1,0.315716,1.18584,8.11554,2.74334,0.0265512,-0.95424 +196,1,0.315301,1.18484,8.10957,2.73759,0.0253198,-0.954594 +197,1,0.315593,1.18553,8.11416,2.74228,0.0272446,-0.955009 +198,1,0.31552,1.1853,8.11111,2.74063,0.0282008,-0.954258 +199,1,0.315791,1.1858,8.11498,2.74154,0.0267633,-0.954479 +200,1,0.315729,1.18564,8.11313,2.74128,0.0276138,-0.954123 +201,1,0.315988,1.18573,8.11389,2.74162,0.0284511,-0.954153 +202,1,0.315653,1.18493,8.11063,2.73942,0.0273624,-0.953926 +203,1,0.315583,1.18492,8.11175,2.74028,0.0266395,-0.954943 +204,1,0.315714,1.18524,8.11073,2.73988,0.0287283,-0.954252 +205,1,0.315364,1.18475,8.10951,2.73682,0.0253562,-0.954904 +206,1,0.315848,1.18598,8.11483,2.74392,0.0286633,-0.954232 +207,1,0.315724,1.18587,8.11456,2.74349,0.0291379,-0.954238 +208,1,0.31554,1.18483,8.10996,2.74016,0.0284587,-0.954052 +209,1,0.315679,1.1849,8.11148,2.73968,0.0266809,-0.954592 +210,1,0.315882,1.18544,8.11417,2.74082,0.0275632,-0.954108 +211,1,0.315523,1.18502,8.11134,2.73956,0.0274179,-0.954236 +212,1,0.315716,1.18543,8.11292,2.74158,0.0295317,-0.953837 +213,1,0.315601,1.18491,8.10907,2.73855,0.0280949,-0.954219 +214,1,0.315559,1.18503,8.11121,2.73979,0.0258934,-0.954335 +215,1,0.315623,1.18518,8.11252,2.74269,0.0278162,-0.954441 +216,1,0.315849,1.18543,8.11304,2.74277,0.0283351,-0.954328 +217,1,0.315739,1.18582,8.11484,2.74347,0.0282182,-0.954832 +218,1,0.31584,1.1856,8.1142,2.74131,0.0274342,-0.954536 +219,1,0.315834,1.18579,8.11428,2.74144,0.0270986,-0.954721 +220,1,0.315735,1.1849,8.11016,2.73907,0.0280271,-0.954314 +221,1,0.315837,1.18541,8.11452,2.74205,0.027778,-0.954212 +222,1,0.315558,1.18515,8.11242,2.74129,0.0291613,-0.953963 +223,1,0.315646,1.18535,8.11245,2.7398,0.0282912,-0.954035 +224,1,0.315352,1.18551,8.11455,2.74311,0.0266308,-0.955064 +225,1,0.315843,1.18598,8.11536,2.7431,0.0279867,-0.954193 +226,1,0.315549,1.18513,8.1122,2.74021,0.0277403,-0.954278 +227,1,0.315833,1.18606,8.11642,2.74245,0.0266739,-0.954877 +228,1,0.315664,1.18523,8.11221,2.74108,0.026773,-0.954993 +229,1,0.315787,1.18566,8.11398,2.74268,0.0278732,-0.954142 +230,1,0.315631,1.18483,8.11002,2.73874,0.0291576,-0.954341 +231,1,0.315866,1.18576,8.11335,2.74052,0.0301807,-0.953805 +232,1,0.31541,1.18514,8.11193,2.74047,0.0280197,-0.954845 +233,1,0.31558,1.18472,8.10956,2.73884,0.0285964,-0.954489 +234,1,0.315693,1.18532,8.11327,2.74266,0.0282846,-0.954194 +235,1,0.315448,1.18424,8.10569,2.73756,0.0292901,-0.953994 +236,1,0.315617,1.18507,8.1114,2.73823,0.0269077,-0.954455 +237,1,0.31567,1.18523,8.11267,2.73997,0.0272684,-0.954546 +238,1,0.315656,1.18527,8.1112,2.74057,0.0287772,-0.954282 +239,1,0.315641,1.18522,8.11209,2.74168,0.0288462,-0.954103 +240,1,0.315666,1.1854,8.11383,2.74162,0.0269784,-0.954608 +241,1,0.315465,1.18489,8.11122,2.73856,0.0266751,-0.955038 +242,1,0.315907,1.18559,8.1149,2.74373,0.026416,-0.954551 +243,1,0.315626,1.18482,8.11044,2.73978,0.0290847,-0.954312 +244,1,0.315774,1.18517,8.11189,2.74151,0.0284896,-0.954152 +245,1,0.315338,1.18481,8.11101,2.73813,0.0269773,-0.954267 +246,1,0.315701,1.18514,8.11147,2.742,0.0276914,-0.954448 +247,1,0.315594,1.18509,8.11165,2.73962,0.0274265,-0.954254 +248,1,0.31557,1.18502,8.11116,2.74144,0.0279902,-0.954421 +249,1,0.315535,1.18497,8.11088,2.73838,0.0283368,-0.954042 +250,1,0.315759,1.18528,8.11135,2.74024,0.02823,-0.954394 +251,1,0.315496,1.1846,8.10875,2.73841,0.028669,-0.954176 +252,1,0.315821,1.18508,8.11165,2.74146,0.0287107,-0.953864 +253,1,0.315702,1.18549,8.11283,2.74386,0.0285133,-0.954283 +254,1,0.315641,1.18522,8.11236,2.74157,0.0294263,-0.954312 +255,1,0.315863,1.186,8.11567,2.74323,0.0257531,-0.954835 +256,1,0.315631,1.18513,8.11138,2.74066,0.0278289,-0.954446 +257,1,0.315706,1.18559,8.1132,2.74324,0.0279423,-0.954393 +258,1,0.315428,1.18452,8.10845,2.73736,0.0287816,-0.953882 +259,1,0.315591,1.18549,8.11276,2.7418,0.0270862,-0.954829 +260,1,0.315484,1.18523,8.11265,2.74034,0.0269894,-0.954272 +261,1,0.315733,1.18545,8.11307,2.74143,0.0269306,-0.954586 +262,1,0.315428,1.18521,8.11182,2.74062,0.0274777,-0.954579 +263,1,0.315738,1.18567,8.11349,2.7426,0.0263819,-0.954606 +264,1,0.315376,1.1849,8.11104,2.73856,0.027657,-0.954133 +265,1,0.315989,1.18487,8.11103,2.73965,0.0289254,-0.954283 +266,1,0.315715,1.18481,8.10977,2.73909,0.0294585,-0.95383 +267,1,0.315957,1.18596,8.11734,2.74366,0.0277607,-0.954518 +268,1,0.315861,1.18565,8.1147,2.74116,0.0277326,-0.954199 +269,1,0.315747,1.18564,8.11363,2.74164,0.027964,-0.954774 +270,1,0.315947,1.18572,8.11486,2.74188,0.0282993,-0.953984 +271,1,0.315491,1.18509,8.11112,2.7402,0.0283405,-0.953849 +272,1,0.315459,1.18503,8.11108,2.73988,0.027342,-0.954463 +273,1,0.315457,1.18509,8.11155,2.73889,0.0275102,-0.954276 +274,1,0.315744,1.1855,8.1133,2.74115,0.0261571,-0.954816 +275,1,0.315685,1.18583,8.11502,2.74212,0.0271391,-0.954634 +276,1,0.315896,1.18538,8.11253,2.74171,0.0280848,-0.954789 +277,1,0.315483,1.18454,8.109,2.73765,0.0269989,-0.954344 +278,1,0.315787,1.18569,8.1138,2.74266,0.0280181,-0.954199 +279,1,0.315426,1.18519,8.11197,2.74103,0.0272796,-0.954175 +280,1,0.315945,1.18577,8.11434,2.74321,0.0290282,-0.954202 +281,1,0.315445,1.18522,8.11166,2.74129,0.028081,-0.954559 +282,1,0.315636,1.18512,8.11026,2.73812,0.0287996,-0.954566 +283,1,0.315546,1.18525,8.11227,2.73911,0.0254956,-0.95499 +284,1,0.315699,1.1855,8.11397,2.74068,0.0281715,-0.954363 +285,1,0.315876,1.18544,8.11365,2.74169,0.0274302,-0.954692 +286,1,0.315932,1.18543,8.11357,2.74287,0.0278143,-0.954299 +287,1,0.315625,1.18548,8.11358,2.74276,0.026527,-0.954622 +288,1,0.315634,1.1848,8.10931,2.73822,0.0274592,-0.954816 +289,1,0.315691,1.18453,8.10851,2.73761,0.0283078,-0.954043 +290,1,0.315508,1.18536,8.113,2.74055,0.0279063,-0.954109 +291,1,0.315728,1.18467,8.10819,2.73804,0.0285543,-0.95416 +292,1,0.315684,1.18545,8.11303,2.74204,0.0288493,-0.954273 +293,1,0.315772,1.18534,8.1129,2.74218,0.028669,-0.953976 +294,1,0.315299,1.18482,8.1096,2.73868,0.027615,-0.954517 +295,1,0.315704,1.18492,8.10971,2.73877,0.0291624,-0.954202 +296,1,0.315359,1.18525,8.11253,2.74118,0.0268223,-0.954478 +297,1,0.315579,1.18466,8.10893,2.73858,0.0272846,-0.954557 +298,1,0.315623,1.18507,8.11098,2.73886,0.0287746,-0.954042 +299,1,0.31559,1.18526,8.11182,2.74045,0.0263704,-0.954972 +300,1,0.3153,1.18443,8.10802,2.73915,0.0294051,-0.954047 +301,1,0.315656,1.18498,8.11018,2.7399,0.0278717,-0.954164 +302,1,0.315752,1.18558,8.11303,2.74095,0.0282785,-0.954281 +303,1,0.315773,1.18517,8.11126,2.7418,0.0281611,-0.953992 +304,1,0.315578,1.18551,8.11167,2.74022,0.027148,-0.954978 +305,1,0.315778,1.18549,8.1121,2.73952,0.026267,-0.954583 +306,1,0.315676,1.18546,8.11273,2.74145,0.0266168,-0.954071 +307,1,0.315796,1.1854,8.11283,2.74072,0.0283307,-0.953849 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_april.txt new file mode 100644 index 0000000..f4b36bd --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_april.txt @@ -0,0 +1,297 @@ +iter,id,x,y,z,r,p,y +0,1,10.718,-0.523217,-1.55538,0.974811,0.256093,-0.314689 +1,1,10.7173,-0.522708,-1.55732,0.973008,0.249962,-0.318422 +2,1,10.7169,-0.523423,-1.55715,0.973766,0.25165,-0.316759 +3,1,10.7233,-0.523193,-1.55887,0.973623,0.24986,-0.3166 +4,1,10.7152,-0.523084,-1.55709,0.97364,0.253266,-0.317964 +5,1,10.7273,-0.523306,-1.55743,0.973582,0.249605,-0.315129 +6,1,10.7266,-0.523372,-1.55748,0.97278,0.249876,-0.316369 +7,1,10.721,-0.523451,-1.55784,0.972705,0.24798,-0.319482 +8,1,10.7158,-0.523338,-1.55727,0.973655,0.251435,-0.317494 +9,1,10.7176,-0.523328,-1.5579,0.973337,0.249377,-0.316952 +9,14,59.2775,28.4081,12.3059,1.54217,0.648661,-0.95303 +10,1,10.7162,-0.523412,-1.55657,0.974399,0.253988,-0.319505 +11,1,10.7147,-0.522657,-1.55554,0.975692,0.259976,-0.317717 +12,1,10.7098,-0.522852,-1.55564,0.975048,0.254765,-0.319999 +13,1,10.7129,-0.522927,-1.55598,0.973646,0.253525,-0.319101 +14,1,10.7133,-0.523271,-1.55649,0.974509,0.252202,-0.31952 +15,1,10.7152,-0.522835,-1.55712,0.973565,0.251841,-0.318568 +16,1,10.7197,-0.523254,-1.55681,0.973663,0.253266,-0.316045 +17,1,10.7216,-0.523137,-1.55675,0.974383,0.256502,-0.314263 +18,1,10.722,-0.523407,-1.55784,0.971948,0.247884,-0.315048 +19,1,10.7118,-0.523278,-1.55569,0.974585,0.256501,-0.315736 +20,1,10.7158,-0.52286,-1.55691,0.973177,0.251445,-0.317313 +21,1,10.7254,-0.523783,-1.55913,0.97282,0.249553,-0.314467 +22,1,10.7204,-0.523101,-1.55728,0.972108,0.245978,-0.318171 +23,1,10.7218,-0.523171,-1.55721,0.971925,0.24822,-0.315517 +24,1,10.7246,-0.523151,-1.55819,0.971944,0.241969,-0.318703 +25,1,10.7106,-0.522971,-1.55604,0.974468,0.253235,-0.318013 +26,1,10.7114,-0.522987,-1.55657,0.973617,0.252255,-0.318941 +27,1,10.7197,-0.523087,-1.55753,0.972901,0.249341,-0.31839 +28,1,10.7239,-0.523612,-1.5576,0.971971,0.245549,-0.317569 +29,1,10.7171,-0.523419,-1.55678,0.97374,0.251938,-0.316201 +30,1,10.7232,-0.523179,-1.55772,0.972724,0.249391,-0.313559 +31,1,10.7192,-0.522937,-1.55764,0.972994,0.252305,-0.315839 +32,1,10.7169,-0.523213,-1.55698,0.973745,0.249459,-0.318928 +33,1,10.7192,-0.523038,-1.55756,0.973752,0.253532,-0.314557 +34,1,10.7188,-0.523064,-1.55613,0.973045,0.248778,-0.320868 +35,1,10.7162,-0.52302,-1.55658,0.974568,0.2543,-0.317374 +36,1,10.7141,-0.523243,-1.55619,0.973432,0.251969,-0.318712 +37,1,10.7143,-0.523063,-1.55678,0.974674,0.255551,-0.316395 +37,26,33.8933,1.06578,9.07955,0.178461,2.77118,1.94675 +38,1,10.7157,-0.523031,-1.55657,0.973178,0.251874,-0.317234 +39,1,10.7226,-0.523221,-1.55803,0.974254,0.253819,-0.314268 +40,1,10.7235,-0.523661,-1.55765,0.974378,0.255668,-0.313093 +41,1,10.7141,-0.523017,-1.5559,0.9734,0.252962,-0.31888 +42,1,10.7084,-0.522834,-1.55565,0.974246,0.254111,-0.318937 +43,1,10.7138,-0.52267,-1.55664,0.973738,0.250767,-0.319555 +44,1,10.7179,-0.523321,-1.55731,0.974185,0.250127,-0.319163 +45,1,10.7231,-0.523533,-1.5583,0.973707,0.253081,-0.311722 +46,1,10.7103,-0.522975,-1.55588,0.975064,0.25831,-0.31787 +47,1,10.7222,-0.523438,-1.55756,0.97471,0.254739,-0.314397 +48,1,10.7171,-0.522904,-1.55725,0.972463,0.248996,-0.31859 +49,1,10.718,-0.523145,-1.55761,0.972739,0.24655,-0.320212 +50,1,10.7235,-0.523339,-1.5584,0.973144,0.245143,-0.319497 +51,1,10.7148,-0.523018,-1.55664,0.974259,0.247014,-0.321531 +52,1,10.7291,-0.523249,-1.55881,0.971501,0.249396,-0.309648 +53,1,10.7231,-0.523742,-1.55809,0.971471,0.247257,-0.314344 +54,1,10.7114,-0.522572,-1.55663,0.973379,0.250657,-0.320723 +55,1,10.7235,-0.523366,-1.55881,0.973229,0.247587,-0.314997 +56,1,10.7244,-0.522793,-1.55882,0.971767,0.244003,-0.320511 +57,1,10.7146,-0.522585,-1.55676,0.973349,0.252877,-0.322153 +58,1,10.7137,-0.523031,-1.55646,0.974117,0.255652,-0.316928 +59,1,10.7129,-0.523091,-1.55645,0.974409,0.252931,-0.318804 +60,1,10.7162,-0.522857,-1.55696,0.973033,0.249265,-0.319545 +61,1,10.7195,-0.523025,-1.55777,0.973477,0.25154,-0.317142 +62,1,10.7146,-0.522862,-1.55762,0.972872,0.249556,-0.320197 +63,1,10.7225,-0.522715,-1.55846,0.972464,0.24515,-0.320028 +64,1,10.7186,-0.522774,-1.55744,0.973812,0.251165,-0.322003 +65,1,10.7177,-0.52313,-1.55755,0.972555,0.251496,-0.315912 +66,1,10.7172,-0.522937,-1.55724,0.973676,0.250247,-0.320101 +67,1,10.7119,-0.522735,-1.55653,0.974085,0.249574,-0.32016 +68,1,10.7083,-0.522607,-1.55624,0.974957,0.253567,-0.321137 +69,1,43.2377,6.14187,11.0016,0.400877,-2.40008,2.27252 +69,1,10.7128,-0.522946,-1.55701,0.973734,0.250858,-0.320321 +70,1,10.7195,-0.523167,-1.55818,0.97273,0.249174,-0.318385 +71,1,10.7147,-0.522968,-1.55711,0.974314,0.251466,-0.320978 +72,1,10.7169,-0.523301,-1.55769,0.973055,0.250623,-0.316646 +73,1,10.7163,-0.523043,-1.55751,0.974262,0.251582,-0.319652 +74,1,10.7132,-0.522782,-1.55679,0.973037,0.252693,-0.317223 +75,1,10.7103,-0.522895,-1.55636,0.974275,0.252911,-0.318761 +76,1,10.7162,-0.523151,-1.55777,0.974162,0.252597,-0.316989 +77,1,10.7111,-0.522819,-1.5569,0.974561,0.254559,-0.318223 +78,1,10.7155,-0.523019,-1.55774,0.975349,0.252656,-0.317056 +79,1,10.7117,-0.522809,-1.55682,0.974207,0.254629,-0.318396 +80,1,10.7237,-0.523144,-1.55904,0.972741,0.248489,-0.315537 +81,1,10.7166,-0.522949,-1.55759,0.973288,0.252192,-0.315775 +82,1,10.7154,-0.522829,-1.55746,0.973227,0.249579,-0.317881 +83,1,10.7168,-0.522902,-1.55726,0.974235,0.253506,-0.319569 +84,1,10.7106,-0.522783,-1.55653,0.974844,0.257479,-0.318439 +85,1,10.7188,-0.523088,-1.55788,0.973252,0.249401,-0.318325 +86,1,10.723,-0.523333,-1.55848,0.972485,0.250124,-0.314873 +87,1,10.7171,-0.52281,-1.55754,0.972793,0.247163,-0.320164 +88,1,10.7196,-0.522984,-1.55813,0.972656,0.250366,-0.316418 +89,1,10.7154,-0.522648,-1.55708,0.973802,0.252158,-0.31826 +90,1,10.7142,-0.52313,-1.55735,0.974708,0.252276,-0.320375 +91,1,10.7199,-0.523028,-1.55772,0.972037,0.249829,-0.316955 +92,1,10.7118,-0.522646,-1.55667,0.973665,0.251561,-0.32016 +93,1,10.7307,-0.52311,-1.55931,0.971145,0.244335,-0.311681 +94,1,10.72,-0.523055,-1.55791,0.97232,0.250616,-0.313508 +95,1,10.7191,-0.52276,-1.55816,0.973522,0.249758,-0.319749 +96,1,10.7171,-0.522763,-1.55792,0.972551,0.250041,-0.319003 +97,1,10.7124,-0.522667,-1.55665,0.975012,0.253796,-0.321184 +98,1,10.7105,-0.522871,-1.55621,0.975015,0.252393,-0.321888 +99,1,10.7163,-0.522561,-1.55759,0.972162,0.248494,-0.317629 +100,1,10.7237,-0.523134,-1.55844,0.972254,0.248823,-0.313349 +101,1,10.719,-0.522586,-1.55779,0.971913,0.246302,-0.316969 +102,1,10.7126,-0.522491,-1.55669,0.974061,0.249709,-0.321948 +103,1,10.7177,-0.522917,-1.55716,0.973083,0.247405,-0.319087 +104,1,10.7107,-0.522268,-1.55597,0.972906,0.253361,-0.32155 +105,1,10.7169,-0.522913,-1.55735,0.973345,0.250791,-0.316702 +106,1,10.713,-0.523244,-1.55659,0.974254,0.252432,-0.319757 +107,1,10.7046,-0.522414,-1.55508,0.975693,0.25642,-0.321854 +108,1,10.7124,-0.523044,-1.55634,0.973699,0.251377,-0.318053 +109,1,10.7259,-0.523583,-1.55879,0.973273,0.25134,-0.30986 +110,1,10.7145,-0.522554,-1.55715,0.973911,0.24871,-0.320947 +111,1,10.713,-0.522571,-1.55667,0.973686,0.250521,-0.320088 +112,1,10.7185,-0.522643,-1.55733,0.972607,0.247057,-0.321957 +113,1,10.7151,-0.522772,-1.55729,0.972435,0.249804,-0.318064 +114,1,10.721,-0.523055,-1.55814,0.971596,0.246362,-0.316301 +115,1,10.7181,-0.522793,-1.55781,0.973111,0.250703,-0.31819 +116,1,10.7179,-0.522939,-1.55749,0.972955,0.251541,-0.315216 +117,1,10.7273,-0.522956,-1.55869,0.971587,0.244218,-0.317061 +118,1,10.7134,-0.522897,-1.55664,0.973753,0.251903,-0.318954 +119,1,10.7139,-0.522555,-1.55669,0.973802,0.250033,-0.320645 +120,1,10.7172,-0.52288,-1.55747,0.972867,0.249144,-0.319544 +121,1,10.7219,-0.523097,-1.55762,0.971664,0.245692,-0.318626 +122,1,10.7144,-0.523126,-1.55669,0.973698,0.252493,-0.317207 +123,1,10.7234,-0.522828,-1.55797,0.972413,0.245246,-0.317918 +124,1,10.7153,-0.522842,-1.55745,0.974208,0.251582,-0.316774 +125,1,10.7111,-0.522691,-1.55673,0.974303,0.253052,-0.321948 +126,1,10.7178,-0.52319,-1.55712,0.973073,0.251582,-0.318528 +127,1,10.7106,-0.522752,-1.55571,0.974149,0.25466,-0.320179 +128,1,10.7204,-0.523169,-1.55752,0.973582,0.248947,-0.317789 +129,1,10.7176,-0.522946,-1.55746,0.973411,0.248178,-0.320414 +130,1,10.7189,-0.522836,-1.55772,0.972279,0.245599,-0.317663 +131,1,10.7191,-0.522992,-1.55754,0.972297,0.248914,-0.316921 +132,1,10.7208,-0.523338,-1.55772,0.973431,0.250607,-0.316148 +133,1,10.7157,-0.522784,-1.5567,0.973439,0.252141,-0.319289 +134,1,10.7121,-0.522534,-1.55647,0.973146,0.25222,-0.319165 +135,1,10.7125,-0.52279,-1.55656,0.973423,0.253017,-0.317883 +136,1,10.7244,-0.523129,-1.55838,0.972058,0.249829,-0.308274 +137,1,10.7099,-0.522548,-1.55656,0.974484,0.253546,-0.32034 +138,1,10.7089,-0.522224,-1.55603,0.974772,0.253991,-0.318748 +139,1,10.7199,-0.523163,-1.55778,0.974019,0.250317,-0.316802 +140,1,10.7223,-0.523083,-1.55814,0.972212,0.24866,-0.314939 +141,1,10.7133,-0.522532,-1.55686,0.973875,0.252303,-0.318709 +142,1,10.7173,-0.522205,-1.55705,0.973106,0.248053,-0.32047 +143,1,10.7143,-0.522166,-1.55717,0.973041,0.249724,-0.320498 +144,1,10.7173,-0.52306,-1.55768,0.973926,0.251769,-0.31572 +145,1,10.7072,-0.52229,-1.55586,0.974221,0.253185,-0.32203 +146,1,10.7204,-0.522851,-1.55824,0.972365,0.247555,-0.318268 +147,1,10.7122,-0.522613,-1.5569,0.973821,0.250851,-0.319818 +148,1,10.7049,-0.522261,-1.55558,0.975499,0.254423,-0.323399 +149,1,10.7205,-0.522877,-1.55749,0.974391,0.251121,-0.320578 +150,1,10.7146,-0.522632,-1.55681,0.974407,0.24955,-0.322807 +151,1,10.7168,-0.522801,-1.55743,0.972757,0.248937,-0.31712 +152,1,10.7237,-0.523016,-1.55839,0.971988,0.245925,-0.318064 +153,1,10.7165,-0.522635,-1.55719,0.972926,0.248656,-0.320917 +154,1,10.7224,-0.522759,-1.55836,0.971909,0.248483,-0.318434 +155,1,10.7154,-0.522698,-1.55736,0.973441,0.249332,-0.31946 +156,1,10.7174,-0.522674,-1.55767,0.973006,0.2453,-0.319824 +157,1,10.7263,-0.523322,-1.55917,0.972218,0.249499,-0.311609 +158,1,10.7147,-0.522665,-1.55722,0.973518,0.249023,-0.321329 +159,1,10.7108,-0.522419,-1.5562,0.974016,0.253615,-0.319767 +160,1,10.7134,-0.522309,-1.55688,0.973214,0.248459,-0.319854 +161,1,10.7153,-0.522716,-1.55725,0.973335,0.251688,-0.317305 +162,1,10.7153,-0.522793,-1.5577,0.972567,0.247153,-0.317692 +163,1,10.7107,-0.522426,-1.55584,0.974513,0.255172,-0.32001 +164,1,10.7189,-0.523028,-1.55736,0.972397,0.249312,-0.318432 +165,1,10.7189,-0.522799,-1.55743,0.972427,0.247498,-0.317614 +166,1,10.7176,-0.522725,-1.55769,0.972353,0.246296,-0.319015 +167,1,10.7207,-0.522622,-1.55816,0.972869,0.247727,-0.318705 +168,1,10.7225,-0.522824,-1.55836,0.972729,0.249173,-0.316237 +169,1,10.7185,-0.522817,-1.55769,0.971909,0.249203,-0.312879 +170,1,10.7134,-0.522647,-1.55654,0.973647,0.251925,-0.319651 +171,1,10.7195,-0.523051,-1.55761,0.97237,0.250803,-0.317356 +172,1,10.7194,-0.522808,-1.55779,0.972335,0.24725,-0.319344 +173,1,10.7061,-0.522154,-1.55545,0.974834,0.252169,-0.32356 +174,1,10.7203,-0.523156,-1.55762,0.972925,0.2508,-0.318369 +175,1,10.7146,-0.522839,-1.55757,0.974018,0.254544,-0.315891 +176,1,10.7154,-0.522525,-1.55669,0.973772,0.249943,-0.320987 +177,1,10.7161,-0.52265,-1.55743,0.973946,0.252334,-0.31625 +178,1,10.7185,-0.52292,-1.55727,0.972711,0.249341,-0.319574 +179,1,10.7269,-0.523103,-1.55922,0.971755,0.247783,-0.313447 +180,1,10.7136,-0.522857,-1.55654,0.975174,0.252314,-0.319793 +181,1,10.7154,-0.522809,-1.55716,0.974576,0.253413,-0.318432 +182,1,10.7076,-0.522689,-1.55609,0.973831,0.25523,-0.315294 +183,1,10.7141,-0.523006,-1.55717,0.974447,0.252564,-0.318942 +184,1,10.7159,-0.52303,-1.55714,0.974111,0.249581,-0.318841 +185,1,10.7163,-0.522759,-1.55734,0.973514,0.249553,-0.318493 +186,1,10.7144,-0.522737,-1.557,0.973462,0.250158,-0.321977 +187,1,10.7181,-0.52301,-1.55733,0.972925,0.250117,-0.31893 +188,1,10.7149,-0.52249,-1.55744,0.973053,0.24717,-0.320446 +189,1,10.7192,-0.522831,-1.55811,0.972772,0.249622,-0.316236 +189,7,30.8529,-14.7757,4.01816,0.0624121,2.13088,2.4945 +190,1,10.7175,-0.522544,-1.55749,0.973136,0.248513,-0.319362 +191,1,10.7202,-0.523017,-1.55852,0.97255,0.246935,-0.318441 +192,1,10.7213,-0.522933,-1.55835,0.97299,0.246768,-0.318806 +193,1,10.7077,-0.52289,-1.55637,0.975201,0.257765,-0.316231 +194,1,10.7118,-0.522405,-1.55649,0.973813,0.252003,-0.32105 +195,1,10.7191,-0.522372,-1.55774,0.973351,0.249382,-0.318251 +196,1,10.7181,-0.522455,-1.5578,0.973071,0.250012,-0.319685 +197,1,10.7261,-0.523031,-1.5591,0.971595,0.241773,-0.320833 +198,1,10.7278,-0.523335,-1.5596,0.97201,0.246583,-0.313027 +199,1,10.711,-0.522404,-1.55687,0.974496,0.252827,-0.321967 +200,1,10.7186,-0.522448,-1.55756,0.97321,0.25252,-0.317853 +201,1,10.7129,-0.522238,-1.55724,0.973482,0.250495,-0.320901 +202,1,10.72,-0.522968,-1.55793,0.973043,0.251225,-0.314668 +203,1,10.7105,-0.522166,-1.55684,0.974965,0.251899,-0.32001 +204,1,10.7132,-0.522728,-1.55738,0.973646,0.253077,-0.314158 +205,1,10.7112,-0.522286,-1.55724,0.975047,0.254995,-0.318701 +206,1,10.7129,-0.522668,-1.5577,0.974396,0.252729,-0.315193 +207,1,10.7207,-0.522723,-1.55832,0.974242,0.247395,-0.320528 +208,1,10.718,-0.522666,-1.55792,0.974282,0.249181,-0.319173 +209,1,10.7191,-0.522821,-1.55765,0.973405,0.250418,-0.318081 +210,1,10.7158,-0.522575,-1.55761,0.974189,0.252425,-0.319176 +211,1,10.7144,-0.522354,-1.55741,0.973606,0.247786,-0.321237 +212,1,10.7147,-0.522372,-1.55759,0.972774,0.250157,-0.318645 +213,1,10.7231,-0.52274,-1.55829,0.972451,0.248372,-0.319021 +214,1,10.7196,-0.522982,-1.55776,0.973067,0.250042,-0.314397 +215,1,10.7159,-0.522401,-1.55753,0.972991,0.247651,-0.321366 +216,1,10.7146,-0.52241,-1.55722,0.973444,0.249635,-0.318923 +217,1,10.7154,-0.522283,-1.55805,0.973391,0.249496,-0.315796 +218,1,10.7144,-0.522059,-1.55706,0.973509,0.246808,-0.321208 +219,1,10.7172,-0.522495,-1.55715,0.972261,0.248294,-0.318748 +220,1,10.7211,-0.522983,-1.55785,0.973929,0.250497,-0.317414 +221,1,10.7123,-0.522424,-1.55672,0.97457,0.252677,-0.320931 +222,1,10.7165,-0.522556,-1.55734,0.972824,0.247341,-0.319732 +223,1,10.7089,-0.522507,-1.556,0.974672,0.253937,-0.318956 +224,1,10.7155,-0.522814,-1.55716,0.974458,0.25086,-0.320165 +225,1,10.7153,-0.522727,-1.55698,0.972964,0.25057,-0.315975 +226,1,10.7149,-0.522695,-1.55698,0.97394,0.251533,-0.31961 +227,1,10.7244,-0.522935,-1.55802,0.972232,0.250265,-0.310209 +228,1,10.7161,-0.522915,-1.55753,0.973229,0.251268,-0.315542 +229,1,10.7138,-0.522337,-1.55715,0.972669,0.249533,-0.316329 +230,1,10.7177,-0.522878,-1.55744,0.972964,0.252576,-0.315061 +231,1,10.7094,-0.522377,-1.55646,0.973158,0.252028,-0.318334 +232,1,10.7216,-0.522793,-1.55796,0.972269,0.247294,-0.316894 +233,1,10.7207,-0.523064,-1.55735,0.972116,0.25153,-0.317309 +234,1,10.7218,-0.523207,-1.5577,0.972428,0.249415,-0.316706 +234,28,27.0848,7.71806,4.97806,1.34564,-2.36714,-1.45235 +235,1,10.7136,-0.522383,-1.55674,0.972123,0.252614,-0.317374 +236,1,10.7141,-0.522989,-1.55697,0.973062,0.251627,-0.318257 +237,1,10.7105,-0.52273,-1.55629,0.974219,0.251846,-0.316719 +238,1,10.714,-0.522949,-1.55684,0.974174,0.25252,-0.316363 +239,1,10.7119,-0.522528,-1.55627,0.974117,0.251561,-0.320432 +240,1,10.7081,-0.522325,-1.5559,0.974469,0.25334,-0.320079 +241,1,10.7086,-0.522518,-1.55624,0.97389,0.254651,-0.316481 +242,1,10.7189,-0.523267,-1.55741,0.972877,0.250391,-0.312774 +243,1,10.7187,-0.522536,-1.55761,0.972264,0.247753,-0.319359 +244,1,10.7171,-0.522291,-1.55686,0.973389,0.248216,-0.320645 +245,1,10.7127,-0.522744,-1.55615,0.973739,0.252112,-0.318995 +246,1,10.7148,-0.52285,-1.55653,0.973176,0.2526,-0.317694 +247,1,10.7101,-0.522689,-1.55617,0.974154,0.253603,-0.316688 +248,1,10.7169,-0.52291,-1.55725,0.972807,0.249577,-0.317969 +249,1,10.713,-0.522735,-1.55638,0.974165,0.253745,-0.316739 +250,1,10.7123,-0.522609,-1.55665,0.97321,0.251135,-0.320437 +251,1,10.7118,-0.522362,-1.5561,0.97436,0.25072,-0.322402 +252,1,10.7154,-0.522847,-1.55704,0.97456,0.250199,-0.320804 +253,1,10.7171,-0.523225,-1.55704,0.973648,0.25003,-0.317522 +254,1,10.7165,-0.522617,-1.55685,0.973615,0.250513,-0.320096 +255,1,10.7153,-0.522579,-1.55691,0.973587,0.250664,-0.317009 +256,1,10.7118,-0.522557,-1.55638,0.973401,0.253666,-0.318738 +257,1,10.7174,-0.522584,-1.55719,0.972927,0.249917,-0.315651 +258,1,10.7143,-0.523103,-1.55724,0.973516,0.252617,-0.316138 +259,1,10.7217,-0.522886,-1.55758,0.972935,0.24982,-0.318215 +260,1,10.7059,-0.522252,-1.55544,0.975069,0.252119,-0.321791 +261,1,10.7251,-0.522654,-1.55862,0.971112,0.24442,-0.31546 +262,1,10.7214,-0.52289,-1.55813,0.972917,0.248959,-0.315813 +263,1,10.7041,-0.52228,-1.55523,0.975208,0.256267,-0.317519 +264,1,10.7152,-0.522585,-1.55695,0.973357,0.249578,-0.319499 +265,1,10.717,-0.522724,-1.55704,0.97329,0.250249,-0.317083 +266,1,10.7111,-0.522709,-1.55631,0.973879,0.252306,-0.319763 +267,1,10.7108,-0.522291,-1.55589,0.974345,0.251795,-0.320734 +268,1,10.7145,-0.522498,-1.55695,0.972885,0.248479,-0.31951 +269,1,10.7132,-0.522886,-1.55665,0.973587,0.25065,-0.318381 +270,1,10.7141,-0.522376,-1.5572,0.972689,0.250219,-0.319043 +271,1,10.7116,-0.522595,-1.55634,0.973652,0.254204,-0.317793 +272,1,10.7134,-0.522724,-1.55653,0.974056,0.255465,-0.317085 +273,1,10.7246,-0.522981,-1.55785,0.971647,0.245888,-0.317092 +274,1,10.7126,-0.522265,-1.55622,0.973522,0.250727,-0.318423 +275,1,10.7112,-0.522619,-1.5558,0.974608,0.254218,-0.320277 +276,1,10.7195,-0.522585,-1.55771,0.973157,0.250132,-0.316963 +277,1,10.7093,-0.522597,-1.55537,0.974447,0.255,-0.321083 +278,1,10.7162,-0.522602,-1.55689,0.974007,0.247458,-0.321492 +279,1,10.719,-0.522841,-1.55749,0.972336,0.247631,-0.317559 +280,1,10.7153,-0.522875,-1.55682,0.973437,0.251805,-0.316809 +281,1,10.7262,-0.522917,-1.5588,0.972405,0.250915,-0.314055 +282,1,10.7156,-0.522779,-1.55705,0.973867,0.251427,-0.319225 +283,1,10.7146,-0.522332,-1.5568,0.97305,0.249584,-0.321252 +284,1,10.7111,-0.522325,-1.55617,0.975012,0.257439,-0.319009 +285,1,10.7025,-0.521764,-1.55461,0.975161,0.253673,-0.324649 +286,1,10.7143,-0.522058,-1.55694,0.972753,0.247407,-0.318616 +287,1,10.7176,-0.522482,-1.55756,0.973429,0.248164,-0.318569 +288,1,10.716,-0.522864,-1.5571,0.974405,0.251756,-0.317905 +289,1,10.7132,-0.522262,-1.55689,0.973283,0.251187,-0.318916 +290,1,10.7189,-0.52262,-1.55723,0.973331,0.247394,-0.317696 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_other.txt new file mode 100644 index 0000000..9d97595 --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-4/pose_other.txt @@ -0,0 +1,297 @@ +iter,id,x,y,z,r,p,y +0,1,0.523255,1.55891,10.783,2.74062,0.0146715,-0.930038 +1,1,0.522807,1.56084,10.7821,2.74171,0.00899472,-0.930047 +2,1,0.523691,1.56142,10.786,2.74517,0.0104447,-0.930294 +3,1,0.523261,1.56241,10.7882,2.74302,0.00919391,-0.930796 +4,1,0.5233,1.56125,10.7837,2.74263,0.0102761,-0.929731 +5,1,0.523502,1.56138,10.7946,2.74631,0.0102053,-0.930777 +6,1,0.523548,1.56132,10.7932,2.74474,0.00963149,-0.929912 +7,1,0.523536,1.56108,10.784,2.7411,0.00854433,-0.930194 +8,1,0.523499,1.56092,10.7812,2.74227,0.0115878,-0.93009 +9,1,0.523557,1.56185,10.7848,2.7452,0.00977978,-0.930485 +9,14,-1.46871,-0.639296,2.2944,1.58259,0.425076,-0.00379567 +10,1,0.523534,1.56017,10.7814,2.73882,0.0118766,-0.930023 +11,1,0.522743,1.55935,10.7812,2.73703,0.0154325,-0.929609 +12,1,0.523065,1.55962,10.7771,2.73963,0.0120951,-0.930368 +13,1,0.523066,1.5598,10.7793,2.74016,0.0103171,-0.929607 +14,1,0.523534,1.56074,10.7822,2.74258,0.00958502,-0.930755 +15,1,0.52302,1.56092,10.7815,2.7418,0.0107109,-0.92991 +16,1,0.523395,1.5606,10.7861,2.74262,0.0121501,-0.929729 +17,1,0.523206,1.56077,10.7896,2.74225,0.0122177,-0.929825 +18,1,0.52358,1.56179,10.7893,2.74725,0.00764799,-0.929893 +19,1,0.523445,1.55975,10.7798,2.74183,0.0138262,-0.929687 +20,1,0.523058,1.56094,10.7836,2.74375,0.00963248,-0.929842 +21,1,0.524002,1.56295,10.7919,2.74658,0.0119042,-0.929914 +22,1,0.523331,1.56097,10.7859,2.74548,0.0081277,-0.930184 +23,1,0.523389,1.5612,10.7893,2.74708,0.00861794,-0.929636 +24,1,0.523252,1.56145,10.7877,2.74543,0.00440428,-0.931378 +25,1,0.52317,1.56007,10.7784,2.74214,0.0110862,-0.93045 +26,1,0.523177,1.56041,10.7779,2.74138,0.0106914,-0.929833 +27,1,0.523337,1.56144,10.7865,2.7441,0.00970118,-0.929962 +28,1,0.523753,1.56114,10.7887,2.74528,0.0066879,-0.930386 +29,1,0.523696,1.56104,10.7862,2.74546,0.0112553,-0.930154 +30,1,0.523427,1.56168,10.7904,2.74801,0.0120086,-0.92991 +31,1,0.523102,1.56123,10.7843,2.74292,0.0135297,-0.929164 +32,1,0.523367,1.56074,10.783,2.74262,0.00823499,-0.930901 +33,1,0.523321,1.56182,10.7883,2.74582,0.0136639,-0.929661 +34,1,0.523219,1.55963,10.7833,2.74078,0.00830802,-0.930229 +35,1,0.52321,1.56047,10.7831,2.74156,0.0130817,-0.93013 +36,1,0.52325,1.55939,10.777,2.73882,0.0103654,-0.929839 +37,1,0.523218,1.56052,10.7804,2.74094,0.0148504,-0.929832 +37,26,-1.09416,-9.27626,34.809,0.695478,2.04971,-0.362348 +38,1,0.523197,1.56046,10.7826,2.74297,0.0101651,-0.929703 +39,1,0.523342,1.56189,10.7895,2.74371,0.0128079,-0.930248 +40,1,0.5238,1.5617,10.7916,2.74415,0.0139225,-0.929905 +41,1,0.523154,1.55963,10.78,2.7404,0.0105086,-0.9295 +42,1,0.523063,1.55969,10.7762,2.74114,0.0118045,-0.929864 +43,1,0.52291,1.56058,10.7808,2.7424,0.00985988,-0.930327 +44,1,0.523304,1.56039,10.7801,2.73907,0.00928399,-0.931093 +45,1,0.523716,1.5625,10.792,2.74747,0.0126255,-0.930101 +46,1,0.523122,1.55992,10.7781,2.7389,0.0138105,-0.929548 +47,1,0.523516,1.56134,10.7887,2.74255,0.0130366,-0.930451 +48,1,0.523075,1.56109,10.7837,2.74348,0.0075376,-0.92987 +49,1,0.52336,1.56138,10.784,2.74372,0.00652334,-0.930684 +50,1,0.52358,1.56222,10.7899,2.7454,0.00633462,-0.931471 +51,1,0.523181,1.56021,10.7796,2.74151,0.00679543,-0.93193 +52,1,0.523275,1.56227,10.7937,2.7482,0.0115715,-0.929162 +53,1,0.523918,1.56196,10.7899,2.74792,0.0082004,-0.929574 +54,1,0.52268,1.55995,10.7748,2.73899,0.0100843,-0.929935 +55,1,0.523629,1.56288,10.7914,2.74835,0.00960297,-0.93096 +56,1,0.523025,1.56245,10.7896,2.74466,0.0056143,-0.930417 +57,1,0.522749,1.56053,10.7807,2.73817,0.00898889,-0.929369 +58,1,0.523109,1.56027,10.7803,2.74014,0.0118212,-0.929588 +59,1,0.523361,1.5605,10.7806,2.7422,0.0121957,-0.930255 +60,1,0.522913,1.56028,10.7797,2.7404,0.00818337,-0.930253 +61,1,0.523088,1.56113,10.7833,2.74109,0.0113005,-0.929986 +62,1,0.523141,1.56172,10.7825,2.74329,0.00814719,-0.929901 +63,1,0.522974,1.56229,10.7889,2.74513,0.00623516,-0.930776 +64,1,0.522852,1.56084,10.7826,2.73771,0.00851383,-0.930318 +65,1,0.523292,1.5613,10.7838,2.74376,0.0113709,-0.929165 +66,1,0.523098,1.56085,10.7823,2.74082,0.00949767,-0.930415 +67,1,0.522951,1.56025,10.7775,2.74183,0.00986043,-0.930904 +68,1,0.522666,1.55961,10.7722,2.7368,0.0109337,-0.930654 +69,1,-7.20254,-12.8871,50.9265,3.02831,0.966077,2.41759 +69,1,0.52306,1.56072,10.7787,2.74034,0.00773152,-0.930521 +70,1,0.523438,1.56229,10.7876,2.74493,0.00852862,-0.929957 +71,1,0.523156,1.56076,10.7801,2.73972,0.0105708,-0.930544 +72,1,0.523453,1.56134,10.7823,2.74335,0.0110402,-0.929834 +73,1,0.523233,1.5612,10.7819,2.74079,0.0111867,-0.930503 +74,1,0.522932,1.56044,10.7786,2.74167,0.0122618,-0.929147 +75,1,0.522917,1.55957,10.7732,2.73835,0.0117668,-0.930262 +76,1,0.523407,1.56206,10.7855,2.7444,0.0107219,-0.930408 +77,1,0.522825,1.56035,10.7756,2.73836,0.0111383,-0.930269 +78,1,0.523216,1.56152,10.7817,2.74249,0.0134701,-0.931251 +79,1,0.523001,1.56068,10.7784,2.74047,0.0129844,-0.929629 +80,1,0.523264,1.56262,10.7888,2.74509,0.00957629,-0.930289 +81,1,0.523201,1.56177,10.7851,2.74523,0.011559,-0.929668 +82,1,0.523001,1.56127,10.7818,2.74361,0.00887855,-0.930378 +83,1,0.523075,1.56102,10.7829,2.73982,0.0116487,-0.929982 +84,1,0.523041,1.56085,10.78,2.74044,0.0137498,-0.929456 +85,1,0.523475,1.56236,10.789,2.74663,0.00935641,-0.930279 +86,1,0.523603,1.56259,10.7912,2.7471,0.0111534,-0.929489 +87,1,0.52301,1.561,10.7812,2.7424,0.00901072,-0.930327 +88,1,0.523135,1.5618,10.7852,2.74374,0.0106273,-0.929573 +89,1,0.522823,1.56107,10.7829,2.74236,0.00951392,-0.930223 +90,1,0.523263,1.56089,10.779,2.73906,0.0109814,-0.930752 +91,1,0.523234,1.5617,10.7873,2.74489,0.00875552,-0.929245 +92,1,0.522806,1.56045,10.778,2.74053,0.0090876,-0.930134 +93,1,0.523241,1.56287,10.7957,2.75058,0.00855345,-0.930117 +94,1,0.523149,1.56127,10.7837,2.74462,0.0132345,-0.929154 +95,1,0.523015,1.56222,10.7869,2.74327,0.00848253,-0.930487 +96,1,0.522885,1.5615,10.7821,2.74149,0.00877064,-0.929558 +97,1,0.522689,1.55992,10.7756,2.73609,0.0109164,-0.930663 +98,1,0.522922,1.55962,10.7747,2.73699,0.0090526,-0.931143 +99,1,0.52277,1.56147,10.7831,2.74489,0.00832423,-0.929672 +100,1,0.523349,1.56255,10.7919,2.74872,0.00954259,-0.929882 +101,1,0.52278,1.5614,10.7841,2.74582,0.00861374,-0.92997 +102,1,0.522741,1.5606,10.7794,2.74115,0.00828024,-0.930872 +103,1,0.52314,1.56092,10.7837,2.74413,0.00823607,-0.93071 +104,1,0.522338,1.55936,10.7746,2.73674,0.00984627,-0.928812 +105,1,0.522994,1.56084,10.7814,2.74232,0.0105616,-0.930145 +106,1,0.523286,1.55992,10.7767,2.7383,0.0104268,-0.93042 +107,1,0.522511,1.55866,10.7696,2.73538,0.0124337,-0.930443 +108,1,0.523288,1.56042,10.7804,2.74365,0.0101888,-0.930226 +109,1,0.523778,1.56295,10.7945,2.74994,0.0128412,-0.930212 +110,1,0.522613,1.56043,10.7777,2.73955,0.00764711,-0.93118 +111,1,0.522763,1.56052,10.7796,2.74158,0.00874187,-0.930433 +112,1,0.522798,1.56083,10.783,2.74093,0.00624327,-0.930359 +113,1,0.522948,1.56104,10.7811,2.7432,0.00917722,-0.929512 +114,1,0.523261,1.56196,10.7874,2.74699,0.00761517,-0.929805 +115,1,0.523103,1.56208,10.7871,2.7449,0.00977593,-0.929829 +116,1,0.522963,1.56086,10.7818,2.74234,0.011158,-0.929666 +117,1,0.523276,1.5627,10.7947,2.74891,0.00728487,-0.930233 +118,1,0.523107,1.56048,10.7799,2.74172,0.0110526,-0.93 +119,1,0.522717,1.56034,10.7792,2.74068,0.00881281,-0.930619 +120,1,0.523075,1.56126,10.7834,2.74267,0.00814919,-0.930075 +121,1,0.523245,1.56101,10.7857,2.74394,0.0075068,-0.929885 +122,1,0.523141,1.5599,10.7774,2.73973,0.0120013,-0.929907 +123,1,0.522839,1.56095,10.7849,2.74277,0.00724644,-0.930843 +124,1,0.522978,1.5611,10.7808,2.74261,0.0116533,-0.930647 +125,1,0.522686,1.55965,10.7722,2.73483,0.0114942,-0.930037 +126,1,0.523265,1.5607,10.783,2.74068,0.00898483,-0.92973 +127,1,0.522843,1.55937,10.7762,2.7379,0.0106466,-0.929714 +128,1,0.523171,1.56051,10.782,2.74069,0.0101761,-0.93079 +129,1,0.523126,1.56108,10.7827,2.74196,0.00808363,-0.930774 +130,1,0.522998,1.56111,10.7827,2.74485,0.00864631,-0.930442 +131,1,0.523129,1.5611,10.784,2.74383,0.00953598,-0.929652 +132,1,0.523471,1.56146,10.7869,2.74391,0.0101785,-0.930341 +133,1,0.52296,1.56027,10.7806,2.74036,0.012024,-0.929517 +134,1,0.5225,1.55945,10.7737,2.73748,0.0107729,-0.929434 +135,1,0.522896,1.56021,10.778,2.74071,0.0109406,-0.929552 +136,1,0.523128,1.5616,10.7875,2.74816,0.0139674,-0.929458 +137,1,0.522724,1.56028,10.7757,2.7391,0.0117701,-0.930135 +138,1,0.522406,1.55987,10.7754,2.74049,0.0124043,-0.930364 +139,1,0.523476,1.56207,10.789,2.74627,0.0106381,-0.93081 +140,1,0.523161,1.56155,10.7864,2.7447,0.0100397,-0.92975 +141,1,0.522656,1.56041,10.7781,2.74031,0.0114563,-0.930026 +142,1,0.522225,1.56002,10.7787,2.73918,0.00851127,-0.930512 +143,1,0.522313,1.56097,10.7806,2.74133,0.00685599,-0.930191 +144,1,0.523218,1.5614,10.7832,2.74366,0.0123131,-0.930337 +145,1,0.52239,1.55919,10.7707,2.73645,0.0113022,-0.929908 +146,1,0.523172,1.56233,10.7883,2.74622,0.00882023,-0.929945 +147,1,0.522701,1.56022,10.7757,2.73945,0.0104093,-0.930357 +148,1,0.522345,1.55912,10.7697,2.73516,0.00992471,-0.930894 +149,1,0.523013,1.56127,10.7868,2.74029,0.00817705,-0.931015 +150,1,0.522788,1.56037,10.7794,2.73896,0.00795613,-0.931248 +151,1,0.522974,1.56124,10.7832,2.74459,0.0087071,-0.930152 +152,1,0.523207,1.56213,10.7897,2.74556,0.00658317,-0.930269 +153,1,0.522921,1.56123,10.7841,2.74315,0.00768091,-0.93016 +154,1,0.522885,1.56187,10.787,2.74268,0.00828701,-0.929403 +155,1,0.522938,1.56127,10.7823,2.74323,0.00897778,-0.930484 +156,1,0.522939,1.56147,10.7835,2.74514,0.00713301,-0.931179 +157,1,0.52358,1.56337,10.7951,2.75022,0.0114242,-0.929611 +158,1,0.522919,1.56113,10.7816,2.74205,0.0080606,-0.930583 +159,1,0.522632,1.5601,10.7776,2.74026,0.0116372,-0.929716 +160,1,0.522385,1.56035,10.7778,2.7412,0.00687005,-0.930731 +161,1,0.522709,1.56063,10.7793,2.7405,0.00924547,-0.930053 +162,1,0.523008,1.56143,10.7811,2.74522,0.00873192,-0.930326 +163,1,0.522478,1.55926,10.7748,2.73681,0.0120765,-0.92981 +164,1,0.523114,1.56078,10.783,2.74169,0.00864057,-0.929654 +165,1,0.522868,1.56057,10.7813,2.74251,0.0094891,-0.930083 +166,1,0.522805,1.56093,10.7806,2.74248,0.00722946,-0.930433 +167,1,0.522778,1.56163,10.785,2.74299,0.00903835,-0.930392 +168,1,0.522919,1.56168,10.786,2.74325,0.0110408,-0.92991 +169,1,0.523065,1.56189,10.7872,2.74934,0.0101958,-0.929415 +170,1,0.522875,1.56055,10.781,2.74179,0.00977365,-0.929971 +171,1,0.523158,1.56124,10.7849,2.74239,0.0093118,-0.92928 +172,1,0.522947,1.56116,10.7831,2.74236,0.00843705,-0.930012 +173,1,0.522329,1.55922,10.7722,2.7376,0.00851466,-0.930906 +174,1,0.52332,1.56131,10.7859,2.74208,0.0101823,-0.92962 +175,1,0.522848,1.56096,10.7787,2.74001,0.0128198,-0.929752 +176,1,0.522649,1.56,10.7787,2.73926,0.0100616,-0.93046 +177,1,0.522778,1.56104,10.7814,2.74242,0.0125428,-0.930164 +178,1,0.523045,1.56081,10.7833,2.74138,0.00827266,-0.929888 +179,1,0.52332,1.5631,10.7937,2.74858,0.0103185,-0.929551 +180,1,0.522924,1.56004,10.7782,2.73899,0.0100934,-0.93136 +181,1,0.522884,1.5608,10.781,2.73983,0.0106236,-0.930571 +182,1,0.522828,1.55982,10.7736,2.74183,0.0146056,-0.92922 +183,1,0.523144,1.56087,10.7799,2.74048,0.0109261,-0.930552 +184,1,0.523228,1.56093,10.7821,2.74297,0.00951962,-0.931075 +185,1,0.522934,1.56083,10.7807,2.74225,0.0111489,-0.930361 +186,1,0.522723,1.56012,10.7768,2.73701,0.00718943,-0.930402 +187,1,0.523231,1.56109,10.7841,2.74263,0.01027,-0.929708 +188,1,0.522607,1.56086,10.7789,2.74156,0.00701529,-0.930805 +189,1,0.523,1.56187,10.7853,2.74469,0.0100409,-0.929931 +189,7,1.4092,-0.388681,2.16711,1.59868,-0.278412,3.10947 +190,1,0.522614,1.5606,10.7797,2.74046,0.00983154,-0.930354 +191,1,0.52303,1.5615,10.7818,2.74139,0.0082634,-0.930426 +192,1,0.523188,1.56217,10.7876,2.74506,0.00837944,-0.930764 +193,1,0.523013,1.56037,10.7754,2.74022,0.0140196,-0.929933 +194,1,0.522565,1.56018,10.7774,2.73928,0.00975484,-0.930028 +195,1,0.522449,1.56102,10.7823,2.74136,0.0100506,-0.930418 +196,1,0.522595,1.56141,10.7833,2.74119,0.00874517,-0.93001 +197,1,0.523213,1.5623,10.7887,2.74415,0.005586,-0.930774 +198,1,0.523589,1.56357,10.7951,2.75015,0.0100588,-0.930123 +199,1,0.52248,1.56027,10.775,2.73677,0.00998622,-0.93042 +200,1,0.522603,1.56136,10.7849,2.74177,0.0107707,-0.929468 +201,1,0.522492,1.56121,10.7801,2.74167,0.00901046,-0.930127 +202,1,0.523184,1.56191,10.7874,2.74589,0.0118799,-0.929725 +203,1,0.522381,1.56076,10.7774,2.74116,0.0104841,-0.931146 +204,1,0.522764,1.56091,10.7781,2.74278,0.0123222,-0.929925 +205,1,0.522426,1.5608,10.7761,2.73886,0.0143249,-0.930194 +206,1,0.522723,1.56112,10.7772,2.742,0.0130803,-0.930556 +207,1,0.522887,1.56179,10.785,2.74179,0.00850454,-0.93171 +208,1,0.522769,1.56137,10.7823,2.74139,0.00912398,-0.931385 +209,1,0.522875,1.56096,10.7826,2.74081,0.0100675,-0.930245 +210,1,0.522778,1.56155,10.7829,2.74147,0.0105605,-0.930335 +211,1,0.522524,1.56107,10.7798,2.7416,0.00688994,-0.931126 +212,1,0.522501,1.56109,10.7792,2.74151,0.00998204,-0.929637 +213,1,0.522966,1.5621,10.7893,2.74374,0.00857543,-0.929839 +214,1,0.523229,1.56165,10.7864,2.74676,0.012671,-0.92995 +215,1,0.522496,1.56089,10.7796,2.74029,0.00660382,-0.930614 +216,1,0.5225,1.56077,10.7795,2.74154,0.00819041,-0.930596 +217,1,0.52251,1.56208,10.783,2.74627,0.0100176,-0.930574 +218,1,0.52231,1.56091,10.7807,2.74323,0.0069295,-0.931232 +219,1,0.522654,1.56073,10.7821,2.74296,0.00848238,-0.929729 +220,1,0.523012,1.56109,10.7842,2.74093,0.010593,-0.930735 +221,1,0.522609,1.56039,10.7778,2.73909,0.0114073,-0.930414 +222,1,0.522829,1.56129,10.7836,2.74452,0.00769635,-0.930465 +223,1,0.52255,1.55942,10.773,2.73831,0.0116165,-0.930397 +224,1,0.522987,1.56095,10.7817,2.74103,0.00915464,-0.931052 +225,1,0.52278,1.56017,10.7781,2.74202,0.0121163,-0.929724 +226,1,0.522817,1.56061,10.7802,2.74029,0.00964947,-0.930401 +227,1,0.522917,1.56125,10.7876,2.74633,0.0127503,-0.929507 +228,1,0.523034,1.56105,10.7809,2.74327,0.0123162,-0.929808 +229,1,0.522453,1.56069,10.7786,2.74373,0.0101533,-0.929851 +230,1,0.522967,1.56104,10.7829,2.7429,0.012046,-0.929325 +231,1,0.52241,1.55985,10.7734,2.73978,0.00986907,-0.929637 +232,1,0.522785,1.56086,10.7827,2.74205,0.00941943,-0.930068 +233,1,0.523203,1.56111,10.7869,2.74253,0.00974158,-0.92881 +234,1,0.523436,1.56171,10.7893,2.74553,0.00918218,-0.929684 +234,28,-9.32731,-6.01407,32.9249,1.62716,2.99211,-2.33453 +235,1,0.522412,1.56001,10.7769,2.73981,0.0112929,-0.92842 +236,1,0.523013,1.56014,10.7768,2.73939,0.0109823,-0.929524 +237,1,0.522929,1.56027,10.7779,2.74384,0.0111012,-0.93064 +238,1,0.522936,1.55995,10.7763,2.73991,0.0126984,-0.930359 +239,1,0.522646,1.55987,10.7771,2.73956,0.00929874,-0.93054 +240,1,0.522289,1.55899,10.7704,2.7364,0.010772,-0.930372 +241,1,0.522529,1.55975,10.7735,2.73988,0.0116421,-0.929684 +242,1,0.523297,1.56103,10.7845,2.74569,0.00983797,-0.930198 +243,1,0.52256,1.56047,10.7795,2.73993,0.00949424,-0.929745 +244,1,0.522527,1.56071,10.7836,2.74279,0.00775357,-0.930742 +245,1,0.522922,1.55999,10.7793,2.74137,0.0102636,-0.930032 +246,1,0.522942,1.56018,10.7804,2.74103,0.0102942,-0.929504 +247,1,0.522809,1.5599,10.7761,2.74161,0.0121688,-0.930075 +248,1,0.522925,1.56038,10.7793,2.74067,0.00952413,-0.929949 +249,1,0.522849,1.56004,10.7785,2.74123,0.0126437,-0.929997 +250,1,0.522696,1.55997,10.7758,2.73878,0.0100301,-0.929695 +251,1,0.522533,1.55964,10.7764,2.73864,0.00959212,-0.930768 +252,1,0.523034,1.56081,10.7815,2.74094,0.00889755,-0.931281 +253,1,0.523275,1.56023,10.7799,2.7411,0.0110007,-0.930513 +254,1,0.522706,1.56021,10.7803,2.73956,0.00958415,-0.930309 +255,1,0.522678,1.5605,10.7804,2.74257,0.0100999,-0.930429 +256,1,0.522622,1.5599,10.7765,2.73905,0.0108497,-0.929332 +257,1,0.52279,1.56114,10.7846,2.74577,0.0102873,-0.930017 +258,1,0.523126,1.56049,10.7775,2.74064,0.012595,-0.92972 +259,1,0.52289,1.56085,10.7851,2.74067,0.00823787,-0.930143 +260,1,0.522369,1.55896,10.7706,2.73794,0.00990746,-0.93115 +261,1,0.522928,1.56251,10.7918,2.74942,0.00785002,-0.929803 +262,1,0.523024,1.56179,10.787,2.74495,0.00955926,-0.930324 +263,1,0.522414,1.55885,10.7694,2.7392,0.0153043,-0.930038 +264,1,0.52266,1.56034,10.7791,2.74059,0.0084783,-0.930455 +265,1,0.522846,1.56066,10.7823,2.74302,0.00992068,-0.930247 +266,1,0.522706,1.55945,10.7736,2.73757,0.0104693,-0.930097 +267,1,0.522433,1.55957,10.7763,2.73954,0.00956894,-0.930642 +268,1,0.522672,1.5606,10.7799,2.74254,0.00828369,-0.930245 +269,1,0.522994,1.55998,10.7767,2.74082,0.0115308,-0.930162 +270,1,0.522509,1.5607,10.7786,2.74121,0.00978992,-0.92953 +271,1,0.522597,1.55966,10.7752,2.73853,0.0116577,-0.929454 +272,1,0.522708,1.55975,10.7765,2.73792,0.0134543,-0.929408 +273,1,0.523092,1.56107,10.7874,2.74431,0.0088842,-0.929801 +274,1,0.52236,1.55965,10.7768,2.74099,0.0103396,-0.930214 +275,1,0.52269,1.55932,10.7759,2.7376,0.0109351,-0.930229 +276,1,0.522575,1.56106,10.7834,2.74158,0.00837669,-0.930372 +277,1,0.522694,1.55891,10.774,2.73668,0.0116168,-0.929737 +278,1,0.522862,1.56074,10.7826,2.74269,0.00761714,-0.931459 +279,1,0.522992,1.5609,10.783,2.74375,0.0097208,-0.929915 +280,1,0.523035,1.5607,10.7821,2.74325,0.0104344,-0.929974 +281,1,0.522977,1.5624,10.7916,2.7445,0.0103178,-0.929455 +282,1,0.522777,1.56023,10.7784,2.73863,0.00979441,-0.930412 +283,1,0.52245,1.56027,10.7789,2.7397,0.00797754,-0.930062 +284,1,0.522402,1.55977,10.7764,2.73691,0.0138634,-0.929625 +285,1,0.521861,1.55792,10.7658,2.73409,0.0105856,-0.930568 +286,1,0.522123,1.56019,10.7774,2.7421,0.00799265,-0.930509 +287,1,0.522602,1.56104,10.782,2.74264,0.00863833,-0.930896 +288,1,0.523089,1.56092,10.7824,2.74266,0.012344,-0.9306 +289,1,0.522489,1.56082,10.7802,2.74256,0.0101086,-0.929816 +290,1,0.522911,1.56141,10.7873,2.74686,0.00790591,-0.931067 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_april.txt new file mode 100644 index 0000000..4d29ced --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_april.txt @@ -0,0 +1,299 @@ +iter,id,x,y,z,r,p,y +0,1,13.1551,-0.231456,-2.07708,0.977903,0.26608,-0.309342 +1,1,13.1572,-0.231418,-2.0728,0.978652,0.264777,-0.313948 +2,1,13.16,-0.231665,-2.07284,0.9774,0.258548,-0.312873 +3,1,13.1637,-0.231216,-2.07505,0.975929,0.260804,-0.310015 +4,1,13.16,-0.231548,-2.07311,0.978502,0.264674,-0.312236 +5,1,13.1541,-0.231121,-2.07063,0.977681,0.260549,-0.313437 +6,1,13.1663,-0.23132,-2.07367,0.97771,0.259856,-0.309597 +7,1,13.1509,-0.230844,-2.07427,0.977521,0.262629,-0.315346 +8,1,13.1529,-0.230706,-2.07636,0.977534,0.268637,-0.308582 +9,1,13.153,-0.230887,-2.07326,0.979135,0.266375,-0.31579 +10,1,13.1858,-0.231866,-2.07754,0.974282,0.252172,-0.302135 +11,1,13.1481,-0.231585,-2.07139,0.979863,0.268357,-0.318039 +12,1,13.1654,-0.231196,-2.07249,0.975893,0.252897,-0.309009 +13,1,13.1636,-0.231115,-2.07425,0.976049,0.254404,-0.312897 +14,1,13.1467,-0.230793,-2.07359,0.980561,0.27144,-0.315892 +15,1,13.1614,-0.231105,-2.07437,0.976991,0.257213,-0.315191 +16,1,13.17,-0.231205,-2.07429,0.975794,0.253042,-0.313422 +17,1,13.153,-0.230828,-2.07239,0.976675,0.253562,-0.315988 +18,1,13.1579,-0.230935,-2.07397,0.976207,0.255247,-0.317091 +19,1,13.1572,-0.231321,-2.07355,0.978205,0.263142,-0.31314 +20,1,13.1481,-0.231205,-2.07139,0.976958,0.266233,-0.314767 +21,1,13.1609,-0.231466,-2.07435,0.975678,0.260312,-0.308899 +22,1,13.1586,-0.230663,-2.07506,0.977005,0.257677,-0.315434 +23,1,13.1617,-0.231961,-2.07444,0.976819,0.262369,-0.313113 +24,1,13.1508,-0.230805,-2.07235,0.978104,0.264407,-0.317139 +25,1,13.1703,-0.231634,-2.07412,0.977016,0.257496,-0.308482 +25,14,76.8822,14.5071,-19.2176,1.38067,-0.266598,0.881837 +26,1,13.1542,-0.231222,-2.07354,0.978358,0.26513,-0.310436 +27,1,13.1581,-0.230724,-2.07397,0.975538,0.25409,-0.318853 +28,1,13.1621,-0.231471,-2.07542,0.97624,0.259639,-0.312056 +29,1,13.1641,-0.231534,-2.07358,0.975799,0.259262,-0.312479 +30,1,13.1543,-0.231237,-2.07206,0.978507,0.264433,-0.315757 +31,1,13.1491,-0.231505,-2.07206,0.978737,0.265385,-0.315235 +32,1,13.1633,-0.231758,-2.07505,0.978674,0.265439,-0.313421 +33,1,13.1485,-0.231301,-2.07238,0.979217,0.26963,-0.312373 +34,1,13.1567,-0.230755,-2.07423,0.976739,0.260861,-0.314002 +35,1,13.1558,-0.230628,-2.0724,0.977723,0.260763,-0.312635 +36,1,13.1496,-0.231161,-2.07142,0.980334,0.268984,-0.310414 +37,1,13.152,-0.231299,-2.07283,0.97891,0.265687,-0.316394 +38,1,13.1527,-0.231178,-2.07324,0.977128,0.259964,-0.316552 +39,1,13.1612,-0.231129,-2.07481,0.979261,0.263222,-0.313848 +40,1,13.1531,-0.230936,-2.07318,0.9785,0.26318,-0.314181 +40,25,8.96213,-4.30648,0.844249,1.89498,2.0508,-1.87906 +41,1,13.1565,-0.231033,-2.07298,0.976441,0.256444,-0.317331 +42,1,13.1651,-0.231263,-2.07405,0.97578,0.254412,-0.310367 +43,1,13.1587,-0.231268,-2.0738,0.978415,0.263679,-0.313707 +44,1,13.1437,-0.231635,-2.0714,0.980141,0.27038,-0.31752 +44,3,25.9122,8.67614,3.60358,1.55031,-3.12776,-2.02327 +45,1,13.1503,-0.231054,-2.07313,0.978206,0.264232,-0.317111 +46,1,13.147,-0.231474,-2.07152,0.979702,0.27123,-0.31271 +47,1,13.1557,-0.231034,-2.07213,0.976561,0.254016,-0.316646 +48,1,13.1467,-0.231296,-2.07149,0.979657,0.268358,-0.31694 +49,1,13.155,-0.231415,-2.07324,0.977491,0.260705,-0.315246 +50,1,13.1461,-0.231215,-2.07215,0.978891,0.264561,-0.319948 +51,1,13.1541,-0.231389,-2.07329,0.97812,0.266609,-0.313512 +52,1,13.1538,-0.231225,-2.07214,0.978355,0.263826,-0.312401 +53,1,13.1553,-0.230871,-2.07186,0.977179,0.261423,-0.314692 +54,1,13.1453,-0.231001,-2.07101,0.978051,0.259514,-0.315994 +55,1,13.1519,-0.231374,-2.07294,0.977966,0.263892,-0.315725 +56,1,13.1559,-0.231619,-2.07359,0.978244,0.263355,-0.315315 +57,1,13.1545,-0.23139,-2.0725,0.978285,0.268371,-0.313105 +58,1,13.1616,-0.230681,-2.07352,0.977032,0.257451,-0.311349 +59,1,13.1489,-0.231589,-2.07128,0.978213,0.267258,-0.314309 +60,1,13.1521,-0.23144,-2.072,0.978252,0.26931,-0.310753 +61,1,13.1635,-0.231216,-2.07425,0.976105,0.255741,-0.31143 +62,1,13.1546,-0.231106,-2.07316,0.978833,0.265393,-0.316607 +63,1,13.1506,-0.230801,-2.07299,0.97722,0.260818,-0.316699 +64,1,13.1682,-0.231035,-2.07513,0.976312,0.256129,-0.308203 +65,1,13.1501,-0.231257,-2.07169,0.979307,0.268644,-0.314739 +66,1,13.1504,-0.231295,-2.07137,0.977506,0.260797,-0.316755 +67,1,13.151,-0.231327,-2.07224,0.978257,0.262711,-0.318109 +67,10,111.077,35.2871,24.8094,0.0354051,-3.02314,-2.9348 +68,1,13.148,-0.231181,-2.07212,0.976883,0.262568,-0.317136 +69,1,13.152,-0.231468,-2.07232,0.979596,0.270064,-0.309299 +70,1,13.1508,-0.231535,-2.07199,0.978285,0.264296,-0.316346 +71,1,13.1519,-0.231076,-2.07191,0.977091,0.261139,-0.31261 +72,1,13.1561,-0.231368,-2.07348,0.977143,0.261212,-0.314298 +73,1,13.1491,-0.231282,-2.07219,0.979114,0.269968,-0.31209 +74,1,13.1535,-0.231598,-2.07263,0.977001,0.262231,-0.316248 +75,1,13.147,-0.230958,-2.07167,0.979106,0.268237,-0.318894 +76,1,13.1557,-0.230924,-2.0724,0.976795,0.259306,-0.31721 +77,1,13.1592,-0.231085,-2.07328,0.976232,0.258611,-0.310627 +78,1,13.1615,-0.231368,-2.07424,0.977901,0.265412,-0.309694 +79,1,13.1555,-0.231475,-2.07262,0.977625,0.264342,-0.313056 +80,1,13.1531,-0.231173,-2.07289,0.977245,0.260071,-0.320874 +81,1,13.159,-0.23137,-2.07339,0.978627,0.262335,-0.310018 +82,1,13.1448,-0.231189,-2.07115,0.979005,0.262799,-0.317914 +83,1,13.1647,-0.231372,-2.07425,0.976258,0.255129,-0.313517 +84,1,13.1628,-0.230835,-2.07464,0.975775,0.254612,-0.312113 +85,1,13.1652,-0.231511,-2.07464,0.977378,0.26167,-0.311881 +86,1,13.1414,-0.231412,-2.07048,0.97985,0.271148,-0.316712 +87,1,13.1518,-0.231106,-2.07249,0.977614,0.262126,-0.314246 +88,1,13.1455,-0.231566,-2.07126,0.979187,0.27018,-0.313357 +89,1,13.1494,-0.230985,-2.07182,0.977892,0.26099,-0.320454 +90,1,13.1564,-0.231644,-2.0734,0.977148,0.263123,-0.313103 +91,1,13.1611,-0.231539,-2.07369,0.978304,0.265613,-0.31281 +92,1,13.1545,-0.231202,-2.07321,0.977649,0.263146,-0.313272 +93,1,13.151,-0.231528,-2.07189,0.979018,0.270647,-0.311707 +94,1,13.1472,-0.231611,-2.0714,0.978886,0.270301,-0.313839 +95,1,13.1475,-0.230675,-2.07148,0.978134,0.263207,-0.317374 +96,1,13.1668,-0.231117,-2.07583,0.975658,0.250371,-0.317146 +97,1,13.1467,-0.231429,-2.07143,0.978371,0.268671,-0.314946 +98,1,13.1618,-0.231342,-2.07444,0.97672,0.257077,-0.315378 +99,1,13.1466,-0.231032,-2.07116,0.979286,0.264229,-0.317224 +100,1,13.1522,-0.231495,-2.07277,0.978784,0.264688,-0.317591 +101,1,13.1532,-0.23176,-2.07287,0.978227,0.266202,-0.311936 +102,1,13.1552,-0.230939,-2.07289,0.976327,0.253859,-0.317524 +103,1,13.1423,-0.231452,-2.07087,0.979454,0.266788,-0.321209 +104,1,13.1415,-0.231031,-2.07044,0.978453,0.269618,-0.313993 +105,1,13.1604,-0.231813,-2.07327,0.977405,0.265808,-0.309248 +106,1,13.1571,-0.231035,-2.07317,0.976007,0.258481,-0.313179 +107,1,13.1543,-0.23144,-2.07324,0.977676,0.265356,-0.313739 +108,1,13.1459,-0.230811,-2.07145,0.980425,0.26963,-0.315234 +109,1,13.1518,-0.231519,-2.07188,0.977842,0.268313,-0.310822 +110,1,13.1532,-0.231244,-2.0724,0.978881,0.264183,-0.315783 +111,1,13.1626,-0.231444,-2.07459,0.977427,0.258832,-0.31784 +112,1,13.1528,-0.231023,-2.07231,0.978409,0.266063,-0.31285 +113,1,13.1489,-0.23105,-2.07147,0.977057,0.260452,-0.31357 +114,1,13.1672,-0.231096,-2.07545,0.975709,0.251743,-0.313031 +115,1,13.1613,-0.231512,-2.07418,0.976379,0.257396,-0.311317 +116,1,13.155,-0.231327,-2.07276,0.977906,0.265367,-0.314973 +117,1,13.1446,-0.231108,-2.0707,0.978766,0.265348,-0.318796 +118,1,13.1608,-0.231133,-2.07353,0.976256,0.25477,-0.315231 +119,1,13.1599,-0.23122,-2.07351,0.976759,0.25954,-0.312937 +120,1,13.1635,-0.231864,-2.0741,0.976865,0.261313,-0.313774 +121,1,13.1618,-0.231333,-2.07354,0.976899,0.260995,-0.311861 +122,1,13.1563,-0.231252,-2.0728,0.977935,0.262875,-0.312544 +123,1,13.171,-0.231584,-2.07549,0.976253,0.257508,-0.307538 +124,1,13.1648,-0.231668,-2.07478,0.977406,0.265086,-0.308579 +125,1,13.1512,-0.231715,-2.07242,0.979184,0.269028,-0.314415 +126,1,13.1609,-0.231345,-2.07418,0.977099,0.258506,-0.316172 +127,1,13.151,-0.231715,-2.07186,0.978747,0.269036,-0.313823 +128,1,13.1601,-0.231144,-2.07387,0.977627,0.261501,-0.31339 +129,1,13.155,-0.231308,-2.07258,0.977126,0.262353,-0.311648 +130,1,13.1562,-0.231433,-2.07279,0.978233,0.268472,-0.310201 +131,1,13.1617,-0.231369,-2.074,0.977496,0.258605,-0.311157 +132,1,13.1562,-0.231403,-2.07288,0.977945,0.267344,-0.307851 +133,1,13.1544,-0.231053,-2.07272,0.977251,0.261147,-0.313529 +134,1,13.1496,-0.23136,-2.07155,0.978067,0.263479,-0.315782 +135,1,13.1697,-0.23132,-2.07534,0.975762,0.253196,-0.313523 +136,1,13.1583,-0.231646,-2.07334,0.977936,0.263718,-0.313672 +137,1,13.1461,-0.231044,-2.07168,0.978394,0.262916,-0.317271 +138,1,13.1442,-0.231099,-2.07098,0.978962,0.265017,-0.320484 +139,1,13.152,-0.231194,-2.0725,0.978569,0.261785,-0.320269 +140,1,13.1576,-0.231731,-2.07315,0.977956,0.262348,-0.310296 +141,1,13.1431,-0.231422,-2.07089,0.978929,0.267521,-0.319578 +142,1,13.1465,-0.231025,-2.07102,0.97816,0.264211,-0.317089 +143,1,13.1536,-0.231031,-2.07287,0.977892,0.264999,-0.314944 +144,1,13.1524,-0.231423,-2.07212,0.97824,0.266881,-0.313235 +145,1,13.1586,-0.231753,-2.0736,0.977915,0.263791,-0.31086 +146,1,13.1542,-0.231165,-2.07242,0.977418,0.262378,-0.313886 +147,1,13.1523,-0.231737,-2.0726,0.979008,0.268552,-0.313317 +148,1,13.1498,-0.231625,-2.07172,0.977186,0.263367,-0.314426 +149,1,13.154,-0.231401,-2.07235,0.977426,0.258614,-0.319107 +150,1,13.146,-0.231804,-2.0715,0.978143,0.264718,-0.320771 +151,1,13.1473,-0.23158,-2.07137,0.977269,0.265839,-0.313389 +152,1,13.1457,-0.231147,-2.07129,0.978656,0.266854,-0.317422 +153,1,13.1553,-0.231358,-2.07267,0.977841,0.262701,-0.315835 +154,1,13.1546,-0.231296,-2.07326,0.977667,0.260653,-0.31671 +155,1,13.1525,-0.231665,-2.07246,0.977512,0.26377,-0.3119 +156,1,13.1511,-0.231471,-2.07223,0.978746,0.269477,-0.313188 +157,1,13.1505,-0.230929,-2.07222,0.977079,0.258561,-0.315891 +158,1,13.1847,-0.231245,-2.07824,0.974158,0.247692,-0.304687 +159,1,13.1504,-0.231395,-2.07236,0.976741,0.261295,-0.312716 +160,1,13.158,-0.230945,-2.07351,0.97729,0.259202,-0.311204 +161,1,13.1555,-0.23154,-2.07252,0.976994,0.263046,-0.312094 +162,1,13.1568,-0.23119,-2.07323,0.97749,0.259029,-0.315426 +163,1,13.1581,-0.231503,-2.07333,0.976552,0.259595,-0.313346 +164,1,13.1461,-0.231227,-2.07134,0.978487,0.263075,-0.317475 +165,1,13.1393,-0.231056,-2.07048,0.97904,0.264729,-0.318453 +166,1,13.1582,-0.231504,-2.07346,0.9772,0.261505,-0.310359 +167,1,13.1468,-0.231666,-2.07104,0.979396,0.267575,-0.316435 +168,1,13.1493,-0.231673,-2.07196,0.978586,0.269262,-0.31415 +169,1,13.15,-0.231539,-2.07215,0.978129,0.267293,-0.312797 +170,1,13.1446,-0.2312,-2.07113,0.979157,0.269355,-0.312029 +171,1,13.1461,-0.231157,-2.07139,0.979435,0.266247,-0.314933 +172,1,13.1638,-0.231204,-2.07437,0.977253,0.260548,-0.304396 +173,1,13.1571,-0.231788,-2.07323,0.977582,0.262612,-0.313897 +174,1,13.1426,-0.231162,-2.07057,0.978878,0.263451,-0.318679 +175,1,13.1624,-0.231777,-2.07452,0.978591,0.265656,-0.306529 +175,8,36.7037,10.8815,-9.90844,0.564353,-0.640523,-0.570663 +176,1,13.154,-0.231115,-2.07271,0.97686,0.258425,-0.317964 +177,1,13.1511,-0.231339,-2.0722,0.978309,0.267456,-0.313946 +178,1,13.1458,-0.230941,-2.07119,0.978804,0.261773,-0.319621 +179,1,13.1462,-0.231047,-2.07138,0.978151,0.260242,-0.319056 +180,1,13.161,-0.231322,-2.07364,0.977525,0.261033,-0.311154 +181,1,13.1438,-0.231565,-2.07127,0.979278,0.270582,-0.315146 +182,1,13.1514,-0.230918,-2.07234,0.977881,0.261332,-0.312713 +183,1,13.1565,-0.231149,-2.07325,0.977332,0.259181,-0.316408 +184,1,13.1535,-0.231359,-2.07266,0.97978,0.265698,-0.314528 +185,1,13.1475,-0.23116,-2.07175,0.97899,0.264938,-0.315215 +186,1,13.1554,-0.23081,-2.07303,0.97672,0.256712,-0.3161 +187,1,13.1472,-0.230977,-2.07219,0.978935,0.264414,-0.31494 +188,1,13.1553,-0.231346,-2.0733,0.978283,0.261839,-0.314492 +189,1,13.1524,-0.231198,-2.07291,0.978099,0.260192,-0.32068 +190,1,13.1554,-0.231351,-2.07274,0.977388,0.26402,-0.311123 +191,1,13.1517,-0.231215,-2.07315,0.976491,0.254787,-0.317856 +192,1,13.144,-0.231186,-2.07063,0.97904,0.269195,-0.315958 +193,1,13.1547,-0.231181,-2.07316,0.977527,0.259565,-0.317888 +194,1,13.1517,-0.231704,-2.07245,0.97775,0.264859,-0.31633 +195,1,13.1452,-0.231204,-2.07133,0.979299,0.266219,-0.315033 +196,1,13.1652,-0.231158,-2.07478,0.977371,0.257915,-0.309774 +197,1,13.155,-0.231172,-2.07357,0.978813,0.260447,-0.31014 +198,1,13.1408,-0.231389,-2.07028,0.979444,0.27271,-0.314817 +199,1,13.1502,-0.231051,-2.07228,0.976597,0.260663,-0.31553 +200,1,13.1475,-0.231005,-2.07149,0.977979,0.262115,-0.316836 +201,1,13.1515,-0.23117,-2.07254,0.977775,0.260536,-0.321315 +202,1,13.1618,-0.231071,-2.0743,0.977408,0.255024,-0.316768 +203,1,13.1525,-0.231212,-2.07205,0.976913,0.258116,-0.318744 +204,1,13.1489,-0.231095,-2.07129,0.977427,0.26446,-0.310584 +205,1,13.1591,-0.23173,-2.07348,0.977824,0.263395,-0.312593 +206,1,13.152,-0.231314,-2.07251,0.979316,0.263137,-0.31891 +207,1,13.1473,-0.231386,-2.0718,0.978581,0.260002,-0.322444 +208,1,13.1643,-0.231396,-2.07494,0.975497,0.254568,-0.313913 +208,16,64.8378,-26.9853,22.5151,2.5248,0.179159,-1.78059 +209,1,13.1512,-0.231342,-2.07186,0.978033,0.265126,-0.313518 +210,1,13.157,-0.231712,-2.07305,0.977249,0.261644,-0.31385 +211,1,13.1513,-0.231055,-2.07223,0.976439,0.255867,-0.31592 +212,1,13.156,-0.231499,-2.07342,0.97715,0.261848,-0.313141 +213,1,13.1595,-0.231414,-2.07363,0.976221,0.256064,-0.313427 +214,1,13.1461,-0.231089,-2.07181,0.978492,0.264581,-0.320291 +215,1,13.1475,-0.23088,-2.07132,0.97819,0.260655,-0.319107 +216,1,13.1466,-0.230996,-2.07166,0.978352,0.262937,-0.317227 +217,1,13.1677,-0.231392,-2.07476,0.97677,0.253466,-0.310795 +218,1,13.1567,-0.23167,-2.07373,0.978609,0.267072,-0.313346 +219,1,13.1621,-0.231383,-2.07415,0.976556,0.262417,-0.306943 +220,1,13.1492,-0.231469,-2.0717,0.979077,0.269889,-0.314788 +221,1,13.1505,-0.231015,-2.07196,0.977138,0.26052,-0.315718 +222,1,13.1563,-0.231196,-2.07235,0.97708,0.261596,-0.312437 +223,1,13.1672,-0.230901,-2.07486,0.976702,0.255047,-0.306639 +224,1,13.1453,-0.23112,-2.07092,0.979373,0.268332,-0.317461 +225,1,13.1496,-0.231085,-2.07261,0.977017,0.256809,-0.317728 +226,1,13.1575,-0.231168,-2.0736,0.976231,0.255359,-0.315175 +227,1,13.1514,-0.231748,-2.0723,0.979166,0.264925,-0.3204 +228,1,13.1521,-0.231778,-2.07181,0.97846,0.266291,-0.314716 +229,1,13.1535,-0.232115,-2.07215,0.978485,0.261668,-0.320378 +230,1,13.1474,-0.23121,-2.07091,0.978213,0.262237,-0.316127 +231,1,13.1568,-0.231602,-2.07315,0.977309,0.265874,-0.310724 +232,1,13.1591,-0.230955,-2.07372,0.976693,0.255651,-0.317593 +233,1,13.1533,-0.231115,-2.07264,0.978143,0.260485,-0.313867 +234,1,13.1547,-0.231258,-2.07293,0.977454,0.257776,-0.315649 +235,1,13.1576,-0.231077,-2.07293,0.976956,0.257246,-0.317918 +236,1,13.1517,-0.231575,-2.072,0.97732,0.264376,-0.310632 +237,1,13.1547,-0.231595,-2.07217,0.977866,0.264173,-0.313071 +238,1,13.1494,-0.23158,-2.07167,0.97813,0.266534,-0.316079 +239,1,13.1573,-0.231965,-2.07326,0.977712,0.263991,-0.311177 +240,1,13.1454,-0.231105,-2.07087,0.977731,0.263779,-0.31485 +241,1,13.155,-0.231269,-2.07313,0.978916,0.264273,-0.315698 +242,1,13.1614,-0.231316,-2.07432,0.976398,0.256054,-0.311254 +243,1,13.1416,-0.231046,-2.07054,0.978977,0.268006,-0.314516 +244,1,13.144,-0.231663,-2.07105,0.978467,0.262812,-0.320234 +244,16,39.5195,-3.47854,12.7657,0.127284,-0.237112,-1.43348 +245,1,13.1698,-0.231507,-2.07547,0.975724,0.254693,-0.308294 +246,1,13.1472,-0.231637,-2.07177,0.979801,0.271437,-0.314593 +247,1,13.1486,-0.230861,-2.07188,0.976877,0.257949,-0.313611 +248,1,13.1467,-0.231056,-2.07116,0.979925,0.269564,-0.315298 +249,1,13.153,-0.231448,-2.07268,0.978598,0.263249,-0.316986 +250,1,13.1649,-0.230917,-2.07462,0.976098,0.254832,-0.315257 +251,1,13.1432,-0.231355,-2.07079,0.979094,0.267818,-0.318507 +252,1,13.16,-0.231317,-2.07374,0.97563,0.251289,-0.316812 +253,1,13.1447,-0.231225,-2.0713,0.980044,0.265619,-0.315543 +254,1,13.1479,-0.231062,-2.07174,0.978314,0.262536,-0.3185 +255,1,13.1551,-0.231315,-2.07282,0.978443,0.256317,-0.316639 +256,1,13.15,-0.231284,-2.07216,0.978784,0.266268,-0.315339 +257,1,13.1582,-0.231117,-2.07335,0.977746,0.262286,-0.310681 +258,1,13.1657,-0.231668,-2.07502,0.976658,0.259131,-0.308817 +259,1,13.1496,-0.230897,-2.07188,0.978036,0.262327,-0.318132 +260,1,13.1577,-0.231585,-2.07378,0.977873,0.265903,-0.313185 +261,1,13.1548,-0.231612,-2.07302,0.978424,0.262878,-0.317008 +262,1,13.1583,-0.231078,-2.07305,0.977815,0.260631,-0.314626 +263,1,13.1533,-0.231176,-2.07275,0.978924,0.263123,-0.31342 +264,1,13.1527,-0.231554,-2.07237,0.978572,0.265869,-0.316141 +265,1,13.1565,-0.231602,-2.07333,0.978235,0.263327,-0.313991 +266,1,13.1492,-0.230555,-2.07267,0.977133,0.258221,-0.318008 +267,1,13.1453,-0.231204,-2.07094,0.978305,0.264975,-0.318413 +268,1,13.1515,-0.23108,-2.07208,0.976382,0.256666,-0.31272 +269,1,13.1595,-0.231501,-2.0738,0.97846,0.266613,-0.310811 +270,1,13.1538,-0.231352,-2.07269,0.978294,0.266306,-0.309216 +271,1,13.1483,-0.230686,-2.0719,0.978973,0.259443,-0.319597 +272,1,13.169,-0.231349,-2.07502,0.975597,0.252894,-0.309062 +273,1,13.1351,-0.231552,-2.06986,0.980643,0.272291,-0.320085 +274,1,13.1511,-0.231465,-2.0719,0.977789,0.262184,-0.318134 +275,1,13.1537,-0.230915,-2.07298,0.976769,0.256873,-0.318493 +276,1,13.1442,-0.231382,-2.07099,0.978641,0.265054,-0.318439 +277,1,13.1536,-0.231602,-2.07232,0.978258,0.267625,-0.310035 +278,1,13.1433,-0.231531,-2.07072,0.978485,0.269406,-0.315729 +279,1,13.1763,-0.231213,-2.07666,0.974247,0.247751,-0.307299 +280,1,13.1445,-0.230942,-2.071,0.979339,0.266251,-0.317802 +281,1,13.1529,-0.231214,-2.07296,0.977827,0.260416,-0.314061 +282,1,13.1498,-0.23133,-2.07217,0.977204,0.260331,-0.312423 +283,1,13.1485,-0.231547,-2.07174,0.977808,0.265276,-0.31704 +284,1,13.1463,-0.231035,-2.07119,0.978281,0.262761,-0.316323 +285,1,13.1564,-0.231348,-2.07332,0.975583,0.253732,-0.313695 +286,1,13.1718,-0.231846,-2.07552,0.976353,0.25754,-0.309035 +287,1,13.1367,-0.231219,-2.07012,0.980468,0.26713,-0.323572 +288,1,13.1556,-0.231354,-2.07303,0.979189,0.2655,-0.313551 +289,1,13.1531,-0.231346,-2.07268,0.977643,0.257998,-0.319891 +290,1,13.161,-0.231051,-2.07457,0.977219,0.255988,-0.307179 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_other.txt new file mode 100644 index 0000000..7ab526c --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-5/pose_other.txt @@ -0,0 +1,299 @@ +iter,id,x,y,z,r,p,y +0,1,0.23101,2.0826,13.2354,2.7428,0.0326039,-0.929086 +1,1,0.230898,2.07559,13.2216,2.73137,0.0356816,-0.929218 +2,1,0.23122,2.07699,13.2323,2.74021,0.028969,-0.930421 +3,1,0.230717,2.07838,13.2313,2.7383,0.0328365,-0.928263 +4,1,0.231063,2.07664,13.2288,2.73516,0.035211,-0.929348 +5,1,0.230664,2.07408,13.2223,2.73647,0.0322084,-0.929768 +6,1,0.23078,2.07626,13.2297,2.73677,0.0341438,-0.930069 +7,1,0.230369,2.0784,13.2231,2.73567,0.029757,-0.92925 +8,1,0.230135,2.08192,13.2335,2.74123,0.030619,-0.928436 +9,1,0.230422,2.07784,13.2277,2.73462,0.0318415,-0.929639 +10,1,0.231402,2.07966,13.2465,2.74587,0.0356937,-0.929045 +11,1,0.231055,2.07494,13.2169,2.72831,0.0335154,-0.929416 +12,1,0.230784,2.07481,13.227,2.74102,0.0337583,-0.930031 +13,1,0.230787,2.07785,13.2326,2.74146,0.0311301,-0.929818 +14,1,0.230186,2.07794,13.2203,2.73009,0.0323021,-0.929737 +15,1,0.230726,2.07851,13.2336,2.73944,0.0287129,-0.930153 +16,1,0.230833,2.0769,13.2333,2.73849,0.0315451,-0.929766 +17,1,0.230566,2.07708,13.2282,2.74323,0.0274407,-0.930795 +18,1,0.230595,2.07752,13.2266,2.73737,0.0290676,-0.929629 +19,1,0.230821,2.07744,13.2281,2.73628,0.0316906,-0.929765 +20,1,0.230619,2.07461,13.2151,2.73071,0.0319175,-0.927626 +21,1,0.230949,2.0776,13.2281,2.7391,0.0327028,-0.928256 +22,1,0.230254,2.07908,13.2301,2.73842,0.0283684,-0.930073 +23,1,0.231492,2.07808,13.2311,2.73612,0.0324358,-0.928514 +24,1,0.23034,2.07634,13.2221,2.7329,0.0310898,-0.929056 +25,1,0.231102,2.07734,13.2374,2.74092,0.0308161,-0.930467 +25,14,-15.8228,20.9311,84.3567,0.878558,-3.12605,1.89542 +26,1,0.230669,2.07731,13.2244,2.73656,0.0335244,-0.929486 +27,1,0.230409,2.07705,13.224,2.7353,0.029288,-0.92906 +28,1,0.230958,2.07929,13.2329,2.73891,0.0285219,-0.929167 +29,1,0.231089,2.07672,13.2305,2.73699,0.0325614,-0.928292 +30,1,0.230801,2.0758,13.2241,2.73343,0.0338746,-0.929231 +31,1,0.231036,2.07588,13.2195,2.73334,0.0336183,-0.929311 +32,1,0.231209,2.0787,13.2329,2.73371,0.0326417,-0.929527 +33,1,0.23078,2.07665,13.2215,2.73417,0.035548,-0.928833 +34,1,0.230325,2.0782,13.2279,2.73748,0.0310269,-0.928885 +35,1,0.230309,2.07706,13.2308,2.74149,0.0335477,-0.929714 +36,1,0.230574,2.07449,13.2158,2.73222,0.0384528,-0.929874 +37,1,0.230748,2.07621,13.2199,2.73043,0.0319485,-0.929482 +38,1,0.230775,2.07723,13.224,2.7362,0.029711,-0.929388 +39,1,0.23071,2.07915,13.2346,2.73755,0.0329893,-0.930556 +40,1,0.230503,2.0781,13.2298,2.73895,0.0300883,-0.930156 +40,25,0.0108527,0.00716777,-0.00110016,1.58128,2.95193,-1.79448 +41,1,0.230597,2.07642,13.2246,2.73569,0.0270053,-0.929795 +42,1,0.230891,2.07799,13.2361,2.74426,0.0299171,-0.929937 +43,1,0.230721,2.07725,13.2271,2.73391,0.0317708,-0.929765 +44,1,0.231104,2.07526,13.2143,2.72844,0.0344153,-0.929151 +44,3,-8.99744,-3.73669,27.0455,2.03208,-0.00880041,1.59013 +45,1,0.230584,2.07747,13.2237,2.73403,0.0296325,-0.929382 +46,1,0.230842,2.07512,13.2162,2.73034,0.03525,-0.928902 +47,1,0.230716,2.07567,13.2242,2.73857,0.0292747,-0.930279 +48,1,0.230819,2.07571,13.2194,2.73145,0.0336142,-0.929334 +49,1,0.231069,2.07763,13.2285,2.73843,0.0317692,-0.929454 +50,1,0.230727,2.07551,13.2138,2.72859,0.0311312,-0.929485 +51,1,0.230799,2.07637,13.2203,2.73103,0.0338009,-0.92855 +52,1,0.2308,2.07693,13.2297,2.73966,0.0321922,-0.929786 +53,1,0.230458,2.07489,13.221,2.73398,0.0348636,-0.928626 +54,1,0.230659,2.07527,13.2181,2.73816,0.0311917,-0.930271 +55,1,0.230872,2.07647,13.2206,2.73269,0.0317834,-0.929085 +56,1,0.231161,2.07789,13.2291,2.73592,0.0306099,-0.929682 +57,1,0.230857,2.07626,13.2246,2.73274,0.035002,-0.928208 +58,1,0.230346,2.07759,13.2333,2.74246,0.0329805,-0.929995 +59,1,0.231106,2.07529,13.2204,2.73348,0.0342398,-0.928382 +60,1,0.230917,2.0762,13.2248,2.73541,0.0360023,-0.928085 +61,1,0.230819,2.0781,13.234,2.74225,0.0298662,-0.929848 +62,1,0.230626,2.07727,13.2266,2.73302,0.0315525,-0.929524 +63,1,0.230359,2.07703,13.2222,2.73553,0.0288722,-0.929362 +64,1,0.23063,2.07885,13.238,2.74417,0.0324085,-0.929958 +65,1,0.230743,2.07532,13.2193,2.73105,0.0357733,-0.928869 +66,1,0.230924,2.07555,13.2227,2.73636,0.0307797,-0.929415 +67,1,0.230867,2.07597,13.2208,2.73234,0.0302592,-0.929607 +67,10,-38.8204,-27.2815,123.039,3.09881,-0.0776426,3.11796 +68,1,0.230729,2.07618,13.2197,2.73419,0.0293629,-0.928522 +69,1,0.230854,2.07578,13.2205,2.73335,0.0374311,-0.929156 +70,1,0.231018,2.07604,13.2225,2.73346,0.0295474,-0.929521 +71,1,0.230603,2.07562,13.2216,2.73743,0.0315869,-0.929219 +72,1,0.230939,2.07757,13.228,2.73744,0.030823,-0.929191 +73,1,0.230687,2.0761,13.2202,2.73267,0.034637,-0.92878 +74,1,0.23116,2.07603,13.2214,2.73322,0.0323545,-0.928425 +75,1,0.230468,2.07543,13.217,2.72857,0.0332152,-0.928673 +76,1,0.230515,2.07565,13.2226,2.73378,0.0309852,-0.928989 +77,1,0.230494,2.07564,13.2213,2.73562,0.0310685,-0.929195 +78,1,0.230851,2.07784,13.2307,2.73671,0.035789,-0.928777 +79,1,0.231001,2.07618,13.2244,2.73483,0.0344099,-0.928595 +80,1,0.230753,2.07663,13.2229,2.73186,0.0274856,-0.929334 +81,1,0.230916,2.07714,13.229,2.73911,0.0351491,-0.930253 +82,1,0.230807,2.07561,13.2187,2.73515,0.0308842,-0.930272 +83,1,0.23094,2.07784,13.2338,2.73993,0.0278821,-0.930174 +84,1,0.230409,2.07776,13.2292,2.73991,0.0299791,-0.929698 +85,1,0.23106,2.07842,13.2354,2.73802,0.0330518,-0.929269 +86,1,0.230892,2.07441,13.2125,2.72896,0.0354594,-0.928643 +87,1,0.230697,2.07744,13.2286,2.73974,0.0295396,-0.929608 +88,1,0.231004,2.07506,13.2159,2.73146,0.0354897,-0.928566 +89,1,0.230585,2.07599,13.2217,2.73311,0.0279556,-0.92973 +90,1,0.231174,2.07675,13.2241,2.73485,0.0341104,-0.928447 +91,1,0.231061,2.07801,13.2344,2.73653,0.0331218,-0.929151 +92,1,0.230702,2.07682,13.2238,2.73533,0.0323166,-0.929132 +93,1,0.230985,2.07597,13.223,2.73342,0.0364898,-0.928348 +94,1,0.231039,2.07571,13.2206,2.73243,0.033144,-0.928496 +95,1,0.230241,2.07535,13.218,2.73322,0.0314859,-0.929297 +96,1,0.230747,2.07947,13.2361,2.74012,0.0238331,-0.930862 +97,1,0.230907,2.07529,13.2173,2.73146,0.034245,-0.928129 +98,1,0.231034,2.07877,13.235,2.74035,0.0301518,-0.929742 +99,1,0.230605,2.07569,13.221,2.73485,0.0307898,-0.930282 +100,1,0.231118,2.07766,13.2286,2.73562,0.0312079,-0.929611 +101,1,0.231286,2.077,13.2254,2.73634,0.0348094,-0.928817 +102,1,0.230633,2.07723,13.2283,2.74045,0.0262558,-0.930382 +103,1,0.231056,2.07513,13.2151,2.72957,0.0323308,-0.929251 +104,1,0.23046,2.07408,13.2109,2.73075,0.0346514,-0.928023 +105,1,0.231269,2.07683,13.2293,2.7365,0.0353546,-0.928299 +106,1,0.230615,2.07643,13.2242,2.73741,0.0320927,-0.92867 +107,1,0.23081,2.07624,13.2201,2.73108,0.0314564,-0.928677 +108,1,0.230294,2.07552,13.2178,2.73142,0.035134,-0.929755 +109,1,0.231013,2.0759,13.2234,2.73551,0.0362173,-0.927887 +110,1,0.230763,2.07676,13.2267,2.73515,0.0302103,-0.930105 +111,1,0.231,2.07816,13.2315,2.7343,0.0282147,-0.929994 +112,1,0.230557,2.07618,13.2235,2.73502,0.0354122,-0.928855 +113,1,0.230673,2.07547,13.2202,2.73855,0.0327003,-0.929133 +114,1,0.230796,2.08,13.2417,2.74592,0.0266907,-0.930635 +115,1,0.230969,2.0765,13.2231,2.73591,0.0315493,-0.929498 +116,1,0.230806,2.07582,13.221,2.73096,0.0342766,-0.928435 +117,1,0.230664,2.07473,13.2161,2.73135,0.0315591,-0.929255 +118,1,0.230796,2.07691,13.2284,2.73867,0.0305172,-0.929784 +119,1,0.230816,2.07646,13.2251,2.73623,0.0349161,-0.928824 +120,1,0.231359,2.07689,13.228,2.73344,0.0329396,-0.92866 +121,1,0.23088,2.07704,13.2303,2.7376,0.0332085,-0.928941 +122,1,0.230818,2.0762,13.2243,2.73587,0.035577,-0.929148 +123,1,0.231094,2.0786,13.2374,2.74153,0.0329497,-0.929562 +124,1,0.231162,2.07871,13.2359,2.7388,0.0352558,-0.92856 +125,1,0.231163,2.07603,13.2204,2.73079,0.034949,-0.92879 +126,1,0.230954,2.07822,13.2324,2.73752,0.0290797,-0.929816 +127,1,0.23126,2.07606,13.2235,2.73361,0.0364182,-0.928269 +128,1,0.230773,2.07895,13.2376,2.74139,0.0304758,-0.929743 +129,1,0.230864,2.07613,13.2238,2.73722,0.0345837,-0.928699 +130,1,0.230818,2.07624,13.2246,2.7335,0.035156,-0.928396 +131,1,0.230967,2.07794,13.2327,2.74113,0.0323321,-0.930261 +132,1,0.230891,2.07635,13.2246,2.73674,0.0389697,-0.928168 +133,1,0.230636,2.0768,13.2263,2.73816,0.031714,-0.929278 +134,1,0.230878,2.07475,13.2163,2.73207,0.0331801,-0.929098 +135,1,0.230989,2.07875,13.2376,2.74102,0.0302639,-0.929863 +136,1,0.231177,2.07716,13.2286,2.73547,0.0329696,-0.929163 +137,1,0.23066,2.0758,13.2181,2.73455,0.0322317,-0.929545 +138,1,0.23064,2.07526,13.2171,2.73083,0.0290529,-0.929669 +139,1,0.230774,2.07668,13.2244,2.73275,0.028213,-0.930182 +140,1,0.231166,2.07608,13.223,2.73568,0.033678,-0.929722 +141,1,0.230926,2.07439,13.2116,2.72761,0.0328539,-0.928642 +142,1,0.230624,2.07525,13.2191,2.73418,0.0322801,-0.929025 +143,1,0.230558,2.07686,13.2249,2.73425,0.0324947,-0.928755 +144,1,0.2309,2.07604,13.2234,2.73402,0.0335954,-0.928679 +145,1,0.23126,2.07764,13.2303,2.73817,0.0331592,-0.929383 +146,1,0.230703,2.07607,13.2236,2.73563,0.032416,-0.92902 +147,1,0.231113,2.07633,13.2223,2.7318,0.0323741,-0.929158 +148,1,0.231223,2.07583,13.2218,2.73636,0.0332162,-0.928427 +149,1,0.231055,2.07619,13.2243,2.73481,0.0296845,-0.929758 +150,1,0.231329,2.07472,13.2128,2.7275,0.0313378,-0.928617 +151,1,0.231048,2.07532,13.2185,2.7345,0.031907,-0.928175 +152,1,0.230681,2.07545,13.218,2.73181,0.0323587,-0.928829 +153,1,0.230894,2.07569,13.221,2.73201,0.0337176,-0.928988 +154,1,0.230903,2.07834,13.2322,2.73913,0.0270429,-0.93007 +155,1,0.231159,2.07607,13.2217,2.73597,0.0333798,-0.928858 +156,1,0.230935,2.0761,13.2219,2.73236,0.0355679,-0.928317 +157,1,0.230568,2.0768,13.2252,2.73961,0.0284489,-0.929897 +158,1,0.230962,2.08204,13.2549,2.75263,0.0311721,-0.930289 +159,1,0.230973,2.07687,13.2248,2.73997,0.0304771,-0.928985 +160,1,0.230539,2.07766,13.2303,2.7414,0.0318053,-0.929986 +161,1,0.231064,2.07574,13.2223,2.73527,0.0348383,-0.928324 +162,1,0.230865,2.07735,13.2288,2.73855,0.0320182,-0.929796 +163,1,0.231067,2.07676,13.2262,2.73708,0.0319105,-0.928944 +164,1,0.230794,2.07549,13.2183,2.73408,0.0304967,-0.929785 +165,1,0.230666,2.07516,13.2145,2.73424,0.0310574,-0.929778 +166,1,0.231086,2.0769,13.2263,2.73854,0.0360211,-0.928921 +167,1,0.231223,2.07531,13.2197,2.73265,0.034187,-0.929252 +168,1,0.231158,2.07565,13.219,2.73133,0.0360121,-0.928058 +169,1,0.231068,2.07584,13.2196,2.73375,0.0366853,-0.92814 +170,1,0.230696,2.07569,13.2193,2.73561,0.0350957,-0.928939 +171,1,0.230654,2.07535,13.2173,2.73332,0.0331391,-0.929871 +172,1,0.230735,2.07847,13.2359,2.74548,0.0349896,-0.929918 +173,1,0.231304,2.07575,13.22,2.73201,0.0356998,-0.928691 +174,1,0.230702,2.07415,13.2115,2.73107,0.0311979,-0.929859 +175,1,0.231171,2.07741,13.2276,2.73637,0.0375668,-0.929465 +175,8,-11.1468,10.1376,37.9162,1.76467,1.22204,0.0756298 +176,1,0.230795,2.07661,13.2246,2.73616,0.030704,-0.929242 +177,1,0.230795,2.07566,13.2195,2.73164,0.034499,-0.928416 +178,1,0.230586,2.07526,13.2175,2.73334,0.0312217,-0.930109 +179,1,0.230697,2.07496,13.215,2.73318,0.0319499,-0.929796 +180,1,0.230804,2.07693,13.2283,2.73708,0.0324058,-0.929693 +181,1,0.231052,2.07509,13.2142,2.73021,0.0363433,-0.928274 +182,1,0.230473,2.07644,13.2234,2.7386,0.0316249,-0.929933 +183,1,0.230758,2.0771,13.227,2.73641,0.0301599,-0.929728 +184,1,0.230854,2.07657,13.2244,2.73378,0.0332061,-0.930365 +185,1,0.230689,2.07536,13.2166,2.733,0.0340482,-0.929606 +186,1,0.230522,2.07734,13.2283,2.74003,0.0302033,-0.929755 +187,1,0.230582,2.07743,13.2257,2.73888,0.0309185,-0.930121 +188,1,0.230976,2.07824,13.232,2.73992,0.0307739,-0.930153 +189,1,0.230746,2.07643,13.2209,2.7311,0.0277443,-0.930112 +190,1,0.230856,2.07658,13.2259,2.73722,0.0335652,-0.92874 +191,1,0.230944,2.07761,13.2256,2.74023,0.027629,-0.930133 +192,1,0.230631,2.07408,13.2123,2.729,0.0345516,-0.9285 +193,1,0.230874,2.07808,13.2312,2.73878,0.0289086,-0.92986 +194,1,0.231141,2.07593,13.2202,2.73117,0.0301594,-0.928785 +195,1,0.230716,2.0752,13.2158,2.73307,0.0338214,-0.929653 +196,1,0.230723,2.07777,13.2307,2.73954,0.0347082,-0.930125 +197,1,0.230769,2.07788,13.2281,2.74206,0.0335753,-0.931065 +198,1,0.23084,2.07457,13.2139,2.73037,0.0354574,-0.928081 +199,1,0.230637,2.07651,13.2228,2.73728,0.0294741,-0.92884 +200,1,0.230664,2.07553,13.2189,2.73533,0.0334691,-0.929227 +201,1,0.230689,2.07582,13.2188,2.72955,0.0273114,-0.929706 +202,1,0.230801,2.07882,13.236,2.74122,0.0286433,-0.930945 +203,1,0.230875,2.07616,13.2243,2.73623,0.0287116,-0.929536 +204,1,0.230555,2.0751,13.2193,2.73703,0.0328487,-0.928812 +205,1,0.231264,2.0772,13.229,2.73625,0.033773,-0.929137 +206,1,0.230959,2.07719,13.2272,2.73496,0.030884,-0.930401 +207,1,0.231024,2.07587,13.219,2.73201,0.0278336,-0.930459 +208,1,0.231055,2.07875,13.2345,2.74111,0.0292614,-0.929377 +208,16,27.4084,-22.917,66.5901,1.90956,-2.17156,1.67203 +209,1,0.230844,2.0755,13.2205,2.7341,0.0337999,-0.928834 +210,1,0.231292,2.07718,13.2291,2.73775,0.0315823,-0.929146 +211,1,0.230708,2.07667,13.2251,2.74071,0.0270875,-0.930067 +212,1,0.231047,2.07787,13.2301,2.73895,0.0300298,-0.92926 +213,1,0.231059,2.07742,13.2297,2.74055,0.0305569,-0.929618 +214,1,0.230603,2.07573,13.2171,2.73,0.0289674,-0.92934 +215,1,0.230513,2.07547,13.2196,2.73451,0.0298142,-0.930002 +216,1,0.230625,2.0759,13.2192,2.73498,0.032298,-0.929499 +217,1,0.230985,2.07732,13.2308,2.74004,0.0328126,-0.9307 +218,1,0.231088,2.07709,13.2246,2.73179,0.0337117,-0.928948 +219,1,0.230877,2.0779,13.2322,2.74105,0.0344707,-0.928609 +220,1,0.230933,2.07578,13.2211,2.73148,0.0343473,-0.928532 +221,1,0.230641,2.07626,13.2235,2.73772,0.0305795,-0.92925 +222,1,0.230692,2.07572,13.2241,2.7361,0.032118,-0.929044 +223,1,0.230573,2.0793,13.2411,2.74877,0.0328635,-0.930702 +224,1,0.230612,2.07511,13.2178,2.73079,0.0322479,-0.929179 +225,1,0.230759,2.07702,13.2232,2.73877,0.0277225,-0.930164 +226,1,0.230835,2.07795,13.2309,2.7414,0.0278216,-0.929965 +227,1,0.231252,2.07572,13.2194,2.72818,0.0307213,-0.929673 +228,1,0.23121,2.0756,13.2224,2.73252,0.0312713,-0.929161 +229,1,0.231707,2.07665,13.2277,2.73374,0.0272818,-0.930236 +230,1,0.230734,2.07484,13.2183,2.7347,0.0298742,-0.929918 +231,1,0.231108,2.07699,13.2274,2.7365,0.0352123,-0.928071 +232,1,0.230673,2.07792,13.2314,2.73911,0.0290528,-0.929975 +233,1,0.230762,2.07692,13.2262,2.73929,0.0328448,-0.930137 +234,1,0.23094,2.07706,13.2267,2.73909,0.0311231,-0.930142 +235,1,0.230731,2.07639,13.2257,2.73536,0.0304746,-0.929635 +236,1,0.230995,2.07517,13.2184,2.73486,0.0335163,-0.928624 +237,1,0.231166,2.07602,13.2252,2.73606,0.0348508,-0.928824 +238,1,0.231078,2.07556,13.2202,2.732,0.0323803,-0.92852 +239,1,0.231452,2.07679,13.2261,2.73617,0.0340502,-0.928988 +240,1,0.230702,2.07514,13.2183,2.73631,0.0329291,-0.928855 +241,1,0.230867,2.07773,13.2298,2.73634,0.0322162,-0.929893 +242,1,0.231033,2.07874,13.2351,2.74468,0.0323185,-0.929805 +243,1,0.230643,2.07554,13.2187,2.73641,0.0344289,-0.92893 +244,1,0.231275,2.07494,13.2146,2.73149,0.0309835,-0.9295 +244,16,4.01151,-14.7637,46.0559,2.65743,-1.38893,-0.725322 +245,1,0.23121,2.07986,13.2433,2.74764,0.0324201,-0.929733 +246,1,0.231055,2.0761,13.2206,2.7312,0.033505,-0.92899 +247,1,0.230546,2.07677,13.225,2.74301,0.0298287,-0.929904 +248,1,0.230566,2.07568,13.2211,2.73288,0.0342168,-0.929406 +249,1,0.230978,2.07646,13.2231,2.733,0.0309781,-0.929831 +250,1,0.230628,2.07918,13.2394,2.7425,0.0281879,-0.929915 +251,1,0.230854,2.07426,13.2115,2.72818,0.0337057,-0.928731 +252,1,0.231049,2.07823,13.2341,2.7431,0.0252292,-0.930499 +253,1,0.23074,2.07579,13.219,2.73491,0.0313567,-0.930778 +254,1,0.230669,2.07548,13.2177,2.73259,0.0321313,-0.929441 +255,1,0.230977,2.07699,13.2273,2.73914,0.028998,-0.931602 +256,1,0.230825,2.07695,13.226,2.73571,0.0313663,-0.929432 +257,1,0.230706,2.07734,13.2296,2.73958,0.0350046,-0.929373 +258,1,0.231195,2.07812,13.232,2.73968,0.0342515,-0.9293 +259,1,0.230516,2.07591,13.221,2.7339,0.0315177,-0.92934 +260,1,0.230988,2.07716,13.2257,2.73251,0.0321007,-0.928725 +261,1,0.231136,2.0765,13.2232,2.73226,0.0314282,-0.929687 +262,1,0.230705,2.07706,13.2296,2.73763,0.0326387,-0.929729 +263,1,0.230753,2.0777,13.2302,2.73978,0.0308658,-0.930561 +264,1,0.231094,2.07585,13.2211,2.73142,0.03482,-0.928792 +265,1,0.231152,2.07745,13.2286,2.73646,0.0322273,-0.92961 +266,1,0.230178,2.07683,13.2215,2.7367,0.0278726,-0.929892 +267,1,0.230715,2.07441,13.2137,2.72991,0.0316835,-0.928905 +268,1,0.230714,2.07555,13.2197,2.73977,0.0322148,-0.929494 +269,1,0.230966,2.07789,13.2315,2.73647,0.0340321,-0.929148 +270,1,0.2309,2.0772,13.2282,2.73972,0.0360372,-0.928995 +271,1,0.230342,2.07646,13.2228,2.73621,0.0283354,-0.931186 +272,1,0.230988,2.07874,13.2388,2.74552,0.0305996,-0.930148 +273,1,0.231028,2.07374,13.2058,2.72549,0.0346695,-0.928885 +274,1,0.231076,2.07601,13.223,2.73417,0.0307444,-0.929229 +275,1,0.230619,2.07724,13.2264,2.73782,0.0287455,-0.929714 +276,1,0.230934,2.0749,13.215,2.73138,0.0317701,-0.92921 +277,1,0.231082,2.07564,13.2212,2.73439,0.0382319,-0.928265 +278,1,0.231066,2.07454,13.2136,2.7307,0.0363789,-0.927727 +279,1,0.230972,2.08091,13.2491,2.75217,0.0295753,-0.930321 +280,1,0.230481,2.07513,13.2166,2.73181,0.0322245,-0.929611 +281,1,0.230831,2.07705,13.2247,2.73838,0.032219,-0.929897 +282,1,0.230882,2.07607,13.2206,2.73876,0.0312794,-0.929577 +283,1,0.231013,2.07521,13.2169,2.73054,0.0310227,-0.928568 +284,1,0.230601,2.07532,13.2184,2.73508,0.0309161,-0.929721 +285,1,0.230978,2.07779,13.2304,2.74365,0.0255509,-0.930121 +286,1,0.231426,2.07896,13.2399,2.74175,0.0334007,-0.929467 +287,1,0.23075,2.074,13.2073,2.72599,0.0304018,-0.930142 +288,1,0.230875,2.07681,13.2258,2.73445,0.0346957,-0.929756 +289,1,0.230969,2.07639,13.2227,2.73396,0.028196,-0.930217 +290,1,0.230703,2.07872,13.2332,2.74679,0.0337761,-0.93082 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_april.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_april.txt new file mode 100644 index 0000000..02eb8ec --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_april.txt @@ -0,0 +1,303 @@ +iter,id,x,y,z,r,p,y +0,1,16.0393,-0.499613,-2.71807,0.999488,0.257108,-0.326655 +1,1,16.0578,-0.49947,-2.72011,0.996997,0.243575,-0.332026 +2,1,16.0749,-0.500713,-2.72344,0.994615,0.236946,-0.322627 +3,1,16.0468,-0.499622,-2.71983,0.998786,0.254059,-0.326952 +4,1,16.049,-0.499773,-2.72373,0.999387,0.249138,-0.327225 +5,1,16.0543,-0.498643,-2.72385,0.99584,0.237332,-0.335568 +6,1,16.0423,-0.49925,-2.72133,0.99942,0.255511,-0.325969 +7,1,16.0499,-0.499755,-2.72224,0.997557,0.246921,-0.332523 +8,1,16.0402,-0.499751,-2.71799,0.999634,0.255123,-0.326146 +9,1,16.0318,-0.499058,-2.71635,1.00067,0.25173,-0.335784 +10,1,16.0409,-0.499145,-2.72,0.996798,0.244743,-0.334932 +11,1,16.0527,-0.500129,-2.72165,0.99663,0.242309,-0.332135 +12,1,16.054,-0.499876,-2.72406,0.996603,0.248227,-0.325403 +13,1,16.0342,-0.49959,-2.7205,0.998915,0.25631,-0.333235 +14,1,16.0427,-0.499775,-2.72028,0.998319,0.252255,-0.333218 +15,1,16.0414,-0.499926,-2.7185,0.9992,0.253072,-0.333642 +16,1,16.0597,-0.50037,-2.72213,0.997323,0.252183,-0.324363 +17,1,16.038,-0.49933,-2.71834,0.999922,0.251814,-0.332837 +18,1,16.0216,-0.498783,-2.71737,0.998234,0.254897,-0.33034 +19,1,16.049,-0.499614,-2.72252,0.998699,0.252576,-0.32383 +20,1,16.0335,-0.499514,-2.71902,0.999463,0.253382,-0.336317 +21,1,16.0566,-0.499559,-2.7231,0.994814,0.234426,-0.331529 +22,1,16.0612,-0.499201,-2.72173,0.994849,0.235198,-0.337152 +23,1,16.0462,-0.499456,-2.7196,0.9986,0.245837,-0.337372 +24,1,16.0395,-0.499632,-2.71936,0.997731,0.255902,-0.326005 +25,1,16.0481,-0.499111,-2.72146,0.99616,0.238647,-0.336398 +26,1,16.0445,-0.499397,-2.72133,0.997221,0.251222,-0.329792 +27,1,16.0481,-0.49977,-2.72136,0.998709,0.245956,-0.338284 +28,1,16.0357,-0.499738,-2.71843,0.997935,0.25152,-0.332342 +29,1,16.0335,-0.498663,-2.71808,0.998152,0.249094,-0.335344 +30,1,16.0439,-0.500049,-2.72027,0.998013,0.242121,-0.338929 +31,1,16.0414,-0.49896,-2.71987,0.99821,0.252924,-0.328634 +32,1,16.0508,-0.499834,-2.72202,0.996192,0.244904,-0.325431 +33,1,16.0427,-0.499257,-2.72066,0.995794,0.239822,-0.33685 +34,1,16.0295,-0.498661,-2.71837,0.998282,0.250051,-0.331233 +35,1,16.0352,-0.498888,-2.71914,0.998234,0.254558,-0.329671 +36,1,16.034,-0.499656,-2.71801,0.999713,0.256014,-0.330164 +37,1,16.0319,-0.498811,-2.7179,0.998314,0.253161,-0.330178 +38,1,16.0352,-0.499467,-2.71943,0.999221,0.257053,-0.329576 +39,1,16.044,-0.499184,-2.72106,0.996899,0.243415,-0.336101 +40,1,16.0336,-0.499118,-2.71911,0.999341,0.264268,-0.319524 +41,1,16.0311,-0.499125,-2.71763,0.998884,0.252789,-0.332807 +42,1,16.0336,-0.499031,-2.71789,0.998835,0.252692,-0.332778 +43,1,16.0541,-0.500023,-2.72152,0.998189,0.247902,-0.331368 +44,1,16.0473,-0.499517,-2.72045,0.996984,0.245313,-0.334444 +45,1,16.0396,-0.499781,-2.71934,0.998328,0.25238,-0.331948 +46,1,16.0533,-0.49888,-2.72254,0.995077,0.239069,-0.33111 +47,1,16.046,-0.499438,-2.72132,0.997924,0.254016,-0.325738 +48,1,16.0428,-0.499814,-2.72008,0.998803,0.25681,-0.324852 +49,1,16.0481,-0.499305,-2.721,0.99861,0.25135,-0.330542 +50,1,16.0598,-0.500246,-2.72242,0.99695,0.246255,-0.329381 +51,1,16.048,-0.499954,-2.72062,1.00015,0.255003,-0.328865 +52,1,16.0426,-0.499354,-2.72051,0.998729,0.253383,-0.328803 +53,1,16.021,-0.498805,-2.71689,0.999936,0.255494,-0.334769 +54,1,16.0364,-0.499437,-2.71924,0.998243,0.254072,-0.325909 +55,1,16.037,-0.499268,-2.71901,0.999114,0.249852,-0.334865 +56,1,16.0343,-0.49944,-2.71869,0.99849,0.258073,-0.326712 +57,1,16.0452,-0.49956,-2.71996,0.999686,0.256661,-0.328476 +58,1,16.0519,-0.500586,-2.72142,0.997055,0.247594,-0.327016 +59,1,16.0315,-0.499158,-2.7182,0.999774,0.257524,-0.32876 +60,1,16.0438,-0.499411,-2.72035,0.997,0.246406,-0.335871 +61,1,16.0411,-0.498927,-2.71998,0.997202,0.249745,-0.329943 +62,1,16.0429,-0.499129,-2.71999,0.997524,0.243326,-0.336845 +63,1,16.0191,-0.499017,-2.71547,0.99943,0.256432,-0.333333 +64,1,16.0468,-0.499891,-2.72056,0.998501,0.24439,-0.334441 +65,1,16.0647,-0.500303,-2.72338,0.996473,0.245888,-0.323028 +66,1,16.0496,-0.499901,-2.72063,0.99826,0.252072,-0.327663 +67,1,16.0349,-0.499035,-2.71892,0.998493,0.25369,-0.328795 +68,1,16.0624,-0.500601,-2.72358,0.996892,0.244926,-0.329826 +69,1,16.0363,-0.499039,-2.71857,0.998275,0.253303,-0.333185 +70,1,16.0376,-0.49949,-2.71925,0.997806,0.252363,-0.331555 +71,1,16.0237,-0.498585,-2.71625,0.999478,0.252503,-0.337076 +72,1,16.0432,-0.499508,-2.71965,0.998508,0.251659,-0.329097 +73,1,16.0347,-0.499139,-2.71845,0.997763,0.253957,-0.335037 +74,1,16.0454,-0.499127,-2.72022,0.997841,0.247024,-0.330353 +75,1,16.0397,-0.499592,-2.71943,0.998806,0.253034,-0.328626 +76,1,16.0352,-0.499811,-2.71875,0.999298,0.255734,-0.326674 +77,1,16.0435,-0.499715,-2.71957,0.997143,0.247883,-0.334399 +78,1,16.0392,-0.499424,-2.71884,0.998336,0.253135,-0.333146 +79,1,16.04,-0.498856,-2.71943,0.997598,0.246875,-0.332392 +80,1,16.0401,-0.499413,-2.71931,0.998184,0.248349,-0.332333 +81,1,16.0414,-0.499317,-2.71959,0.997903,0.249873,-0.335009 +82,1,16.0407,-0.499408,-2.71935,0.997211,0.252012,-0.329106 +83,1,16.0399,-0.500072,-2.71931,0.999983,0.252681,-0.333291 +84,1,16.035,-0.498985,-2.71859,0.998258,0.253408,-0.326593 +85,1,16.0424,-0.499559,-2.71908,0.999113,0.25448,-0.324238 +86,1,16.0433,-0.499441,-2.71992,0.997588,0.242872,-0.334715 +87,1,16.0321,-0.498569,-2.71783,0.997211,0.245991,-0.337484 +88,1,16.0453,-0.500244,-2.71998,1.00029,0.258403,-0.325122 +89,1,16.0417,-0.498851,-2.72002,0.997307,0.243513,-0.331594 +90,1,16.0377,-0.498949,-2.71883,0.996606,0.244592,-0.333478 +91,1,16.032,-0.499097,-2.71786,0.999254,0.256093,-0.328852 +92,1,16.0253,-0.498978,-2.71655,0.999647,0.259218,-0.329615 +93,1,16.0375,-0.498945,-2.71912,0.999517,0.258304,-0.326723 +94,1,16.0317,-0.499107,-2.71762,0.998601,0.252195,-0.332379 +95,1,16.025,-0.498982,-2.71642,0.999521,0.257235,-0.332891 +96,1,16.0326,-0.499676,-2.71765,0.998952,0.252443,-0.333891 +97,1,16.0358,-0.499657,-2.71821,0.999974,0.254844,-0.328894 +98,1,16.0384,-0.499413,-2.71821,0.999214,0.252919,-0.331062 +99,1,16.0424,-0.499167,-2.7196,0.997373,0.250923,-0.328898 +100,1,16.0504,-0.500343,-2.72101,0.997311,0.24064,-0.335341 +101,1,16.0385,-0.499125,-2.7184,0.999861,0.260433,-0.327344 +102,1,16.0343,-0.499037,-2.71845,0.997353,0.253145,-0.327789 +103,1,16.0356,-0.498938,-2.71822,0.997553,0.251215,-0.330618 +104,1,16.0452,-0.499942,-2.72025,0.997982,0.244322,-0.332853 +105,1,16.0396,-0.499289,-2.71934,0.997493,0.249523,-0.33124 +106,1,16.0483,-0.499477,-2.72055,0.996698,0.244604,-0.333371 +107,1,16.0442,-0.499452,-2.72017,0.997495,0.24983,-0.326879 +108,1,16.04,-0.500105,-2.71845,0.998556,0.251326,-0.331757 +109,1,16.063,-0.499589,-2.72347,0.995437,0.2382,-0.331846 +110,1,16.0317,-0.499273,-2.7181,0.998363,0.251695,-0.33142 +111,1,16.0262,-0.499433,-2.71681,1.0002,0.252577,-0.33645 +112,1,16.0326,-0.499363,-2.71775,0.998274,0.25063,-0.331906 +113,1,16.0347,-0.499882,-2.7182,0.998204,0.252188,-0.332384 +114,1,16.0362,-0.499191,-2.71844,1.00014,0.2568,-0.328316 +115,1,16.0335,-0.499516,-2.7182,0.998299,0.25149,-0.328032 +116,1,16.0353,-0.499305,-2.71805,0.998987,0.249417,-0.33332 +117,1,16.0334,-0.498849,-2.71785,0.997939,0.244347,-0.337424 +118,1,16.0307,-0.499148,-2.71729,0.997924,0.249768,-0.332046 +119,1,16.034,-0.499282,-2.7185,0.998364,0.255615,-0.329287 +120,1,16.0371,-0.499008,-2.71863,0.998093,0.251797,-0.329955 +121,1,16.0489,-0.499548,-2.72101,0.997098,0.241177,-0.333282 +122,1,16.0344,-0.499625,-2.71789,0.998248,0.252566,-0.329229 +123,1,16.0473,-0.499861,-2.7204,0.996302,0.254024,-0.324747 +124,1,16.0411,-0.499154,-2.71967,0.998198,0.256107,-0.322795 +125,1,16.0305,-0.49892,-2.71786,0.999202,0.254914,-0.331209 +126,1,16.0397,-0.499199,-2.71882,0.997938,0.247922,-0.333666 +127,1,16.0365,-0.50006,-2.71828,1.0007,0.260671,-0.32833 +128,1,16.0435,-0.500194,-2.7196,0.998426,0.25444,-0.322301 +129,1,16.0405,-0.499712,-2.71965,0.998197,0.249645,-0.329832 +130,1,16.0302,-0.499177,-2.71731,0.999997,0.26263,-0.32459 +130,2,39.9682,10.3308,4.49501,2.70417,-1.74642,2.58297 +131,1,16.0447,-0.499066,-2.72012,0.99757,0.250861,-0.325982 +132,1,16.0563,-0.499953,-2.7218,0.997487,0.249078,-0.326415 +133,1,16.0258,-0.498931,-2.71694,0.999444,0.2568,-0.332266 +134,1,16.0471,-0.499852,-2.72045,0.997444,0.255709,-0.317712 +135,1,16.0396,-0.499123,-2.719,0.998151,0.248368,-0.332043 +136,1,16.0293,-0.499073,-2.71714,0.998216,0.251789,-0.335394 +137,1,16.037,-0.499039,-2.71854,0.998362,0.248107,-0.334075 +138,1,16.0327,-0.498998,-2.71735,0.99907,0.252419,-0.334243 +139,1,16.0458,-0.499894,-2.71979,0.99811,0.247743,-0.332832 +140,1,16.058,-0.499458,-2.72226,0.995497,0.243496,-0.328689 +141,1,16.0382,-0.499332,-2.71909,0.998974,0.25855,-0.320785 +142,1,16.0398,-0.49917,-2.71886,0.997848,0.248054,-0.331971 +143,1,16.0411,-0.499936,-2.71938,0.998681,0.24782,-0.335742 +144,1,16.0426,-0.499236,-2.71934,0.998446,0.250431,-0.329073 +145,1,16.0704,-0.500997,-2.72376,0.996155,0.242815,-0.328775 +146,1,16.02,-0.498627,-2.71513,0.999913,0.252791,-0.338718 +147,1,16.0346,-0.498872,-2.71765,0.999092,0.251759,-0.333101 +148,1,16.0433,-0.499184,-2.71969,0.99675,0.242913,-0.335017 +149,1,16.0391,-0.498781,-2.71906,0.998071,0.255329,-0.324192 +150,1,16.0459,-0.499335,-2.7197,0.997854,0.246621,-0.332752 +151,1,16.027,-0.498854,-2.71713,0.998642,0.252851,-0.335586 +152,1,16.0596,-0.500475,-2.7226,0.996892,0.245357,-0.326578 +153,1,16.0404,-0.500397,-2.71962,0.998281,0.250589,-0.330236 +154,1,16.0602,-0.50074,-2.72262,0.997536,0.249827,-0.322344 +155,1,16.0425,-0.499541,-2.7196,0.999636,0.257466,-0.323117 +156,1,16.0545,-0.49965,-2.72116,0.996606,0.244477,-0.330958 +157,1,16.0386,-0.499604,-2.71854,0.999165,0.250075,-0.336234 +158,1,16.0371,-0.499148,-2.71817,0.998809,0.251571,-0.334387 +159,1,16.0346,-0.499094,-2.71864,0.996257,0.245944,-0.333256 +160,1,16.0361,-0.499127,-2.71815,0.999506,0.252199,-0.332465 +161,1,16.0335,-0.498993,-2.71873,0.996671,0.251392,-0.332596 +162,1,16.0361,-0.499621,-2.71818,0.999739,0.257199,-0.325658 +163,1,16.0346,-0.499752,-2.71795,0.997952,0.249772,-0.331532 +164,1,16.0478,-0.500089,-2.72011,0.997844,0.256161,-0.320668 +165,1,16.0488,-0.499954,-2.72096,0.998067,0.247406,-0.32554 +166,1,16.0384,-0.499132,-2.71878,0.998099,0.252563,-0.330991 +167,1,16.0375,-0.499487,-2.71877,0.99831,0.249449,-0.32883 +168,1,16.0285,-0.499254,-2.7169,0.998839,0.24861,-0.336838 +169,1,16.0421,-0.500126,-2.71914,0.998868,0.251525,-0.327499 +170,1,16.0411,-0.499273,-2.71981,0.998446,0.251727,-0.324192 +171,1,16.0283,-0.49933,-2.71649,0.999476,0.257122,-0.330221 +172,1,16.0432,-0.49971,-2.71995,0.998213,0.250251,-0.328177 +173,1,16.0353,-0.499616,-2.71772,0.999647,0.252335,-0.336034 +174,1,16.0538,-0.500077,-2.72172,0.996892,0.251234,-0.319178 +175,1,16.0449,-0.499689,-2.72025,0.997688,0.249776,-0.325634 +176,1,16.0476,-0.498719,-2.71994,0.997051,0.252852,-0.324924 +177,1,16.0454,-0.499161,-2.71989,0.997485,0.237803,-0.339753 +178,1,16.0445,-0.499857,-2.72003,0.998102,0.248048,-0.326428 +179,1,16.0448,-0.499544,-2.71999,0.997413,0.247356,-0.327801 +180,1,16.0296,-0.498695,-2.71668,0.997907,0.255895,-0.331979 +181,1,16.051,-0.500237,-2.72169,0.998089,0.250761,-0.325104 +182,1,16.0404,-0.499335,-2.71937,0.997863,0.252976,-0.326948 +183,1,16.0475,-0.499763,-2.72065,0.996888,0.244948,-0.33049 +184,1,16.0522,-0.499962,-2.72133,0.996726,0.244642,-0.328813 +185,1,16.0409,-0.499187,-2.71887,0.997763,0.248057,-0.330246 +186,1,16.0293,-0.499062,-2.71721,0.998719,0.248532,-0.339092 +187,1,16.0356,-0.499124,-2.71781,0.99805,0.248114,-0.333877 +188,1,16.0355,-0.499844,-2.71774,1.00028,0.255689,-0.332835 +189,1,16.0516,-0.499557,-2.72124,0.996389,0.238776,-0.332854 +190,1,16.0335,-0.498697,-2.71793,0.997894,0.241466,-0.341824 +191,1,16.0493,-0.499263,-2.72036,0.997419,0.249008,-0.329459 +192,1,16.046,-0.499878,-2.721,0.997522,0.254327,-0.319805 +193,1,16.0357,-0.498854,-2.71854,0.997516,0.249678,-0.336116 +194,1,16.0345,-0.499234,-2.71792,0.997548,0.248785,-0.335181 +195,1,16.0393,-0.49966,-2.71918,1.00024,0.253452,-0.332462 +196,1,16.0295,-0.499253,-2.71668,0.999486,0.25516,-0.33332 +197,1,16.0345,-0.499257,-2.71782,0.998402,0.251268,-0.331858 +198,1,16.0454,-0.499878,-2.71964,0.998549,0.254861,-0.326785 +199,1,16.0506,-0.499398,-2.72083,0.997877,0.246019,-0.329923 +200,1,16.0303,-0.499144,-2.71727,0.999861,0.257981,-0.329134 +201,1,16.0391,-0.49959,-2.71863,0.999673,0.25962,-0.326063 +202,1,16.0465,-0.499553,-2.72067,0.998002,0.25214,-0.324243 +203,1,16.0395,-0.499493,-2.71908,0.998203,0.24914,-0.33208 +204,1,16.0378,-0.49938,-2.71889,0.999143,0.25299,-0.330001 +205,1,16.0373,-0.499142,-2.7184,0.999162,0.249965,-0.332628 +206,1,16.0504,-0.499916,-2.72098,0.998901,0.256611,-0.31989 +207,1,16.0432,-0.49941,-2.71937,0.998152,0.251951,-0.326166 +208,1,16.0489,-0.500189,-2.72001,0.997111,0.249289,-0.328512 +209,1,16.026,-0.500081,-2.71619,1.00059,0.25829,-0.333612 +210,1,16.0474,-0.500261,-2.72009,0.998225,0.251836,-0.32965 +211,1,16.0325,-0.49898,-2.71777,0.999637,0.255425,-0.333191 +212,1,16.0527,-0.499891,-2.72149,0.996782,0.241695,-0.333325 +213,1,16.0386,-0.499228,-2.7187,0.998061,0.249047,-0.333531 +214,1,16.0437,-0.49965,-2.72005,0.997577,0.254537,-0.3257 +215,1,16.0304,-0.499185,-2.71746,0.99997,0.253695,-0.335588 +216,1,16.038,-0.499214,-2.71889,0.999043,0.254854,-0.327405 +217,1,16.0383,-0.499076,-2.71866,0.998034,0.250012,-0.329302 +218,1,16.0514,-0.499934,-2.72105,0.996915,0.240285,-0.334753 +219,1,16.0288,-0.498672,-2.71675,1.00002,0.256542,-0.330263 +220,1,16.03,-0.499359,-2.71711,0.998914,0.254913,-0.327544 +221,1,16.0451,-0.499602,-2.71974,0.997479,0.249187,-0.327732 +222,1,16.054,-0.499553,-2.72143,0.996202,0.242593,-0.333509 +223,1,16.0282,-0.498786,-2.71687,0.998286,0.250264,-0.332985 +224,1,16.0252,-0.499509,-2.71633,1.00072,0.258692,-0.335184 +225,1,16.0451,-0.499594,-2.72006,0.996732,0.243325,-0.334598 +226,1,16.0299,-0.499077,-2.71787,0.999891,0.247826,-0.338083 +227,1,16.0389,-0.499377,-2.71874,0.997758,0.250359,-0.329253 +228,1,16.0514,-0.499666,-2.72098,0.996614,0.240278,-0.332187 +229,1,16.0435,-0.499152,-2.71992,0.997206,0.244128,-0.335233 +230,1,16.0336,-0.499408,-2.7177,0.997853,0.25075,-0.334555 +230,14,99.152,-44.035,37.1204,0.0576039,-0.159042,-1.16602 +231,1,16.0401,-0.50006,-2.719,1.00114,0.261098,-0.325952 +232,1,16.043,-0.49927,-2.71953,0.997109,0.243946,-0.333187 +233,1,16.0281,-0.499288,-2.71687,0.999138,0.255611,-0.330002 +234,1,16.0287,-0.499515,-2.71688,1.0005,0.25955,-0.329718 +235,1,16.0405,-0.499784,-2.7195,0.998582,0.254339,-0.331099 +236,1,16.0407,-0.499655,-2.7192,0.998064,0.251555,-0.328759 +237,1,16.0568,-0.500406,-2.72187,0.997361,0.245366,-0.330857 +238,1,16.0411,-0.499699,-2.71873,0.997274,0.245756,-0.332992 +239,1,16.0549,-0.499709,-2.72155,0.997565,0.240914,-0.336448 +240,1,16.0358,-0.498878,-2.71788,0.997435,0.249552,-0.329356 +240,23,71.631,-6.54051,20.3424,2.76395,-2.27631,1.94603 +241,1,16.0408,-0.499428,-2.7192,0.998088,0.246184,-0.333844 +242,1,16.0179,-0.498858,-2.71488,1.00151,0.256931,-0.33807 +243,1,16.0341,-0.499549,-2.71798,0.99962,0.259201,-0.322867 +244,1,16.0253,-0.49941,-2.71634,1.00055,0.260489,-0.332074 +245,1,16.0337,-0.499412,-2.71786,0.998548,0.244504,-0.337182 +246,1,16.0425,-0.49953,-2.71966,0.996781,0.244308,-0.334633 +247,1,16.0422,-0.499829,-2.71956,0.998564,0.249472,-0.332584 +248,1,16.055,-0.500342,-2.72178,0.997635,0.251304,-0.322887 +249,1,16.0437,-0.499902,-2.71935,0.998144,0.253046,-0.326812 +250,1,16.0405,-0.498969,-2.71926,0.998372,0.242013,-0.339136 +251,1,16.0392,-0.499932,-2.71865,0.998505,0.254643,-0.325791 +252,1,16.0482,-0.499906,-2.72021,0.997661,0.245503,-0.330336 +253,1,16.0408,-0.499013,-2.71958,0.998383,0.252155,-0.329323 +254,1,16.0275,-0.499416,-2.7167,0.999649,0.255773,-0.337382 +255,1,16.0493,-0.499463,-2.72099,0.997175,0.250516,-0.32518 +256,1,16.0371,-0.499045,-2.71906,0.997686,0.246704,-0.331634 +257,1,16.047,-0.499238,-2.72028,0.998175,0.241199,-0.33647 +258,1,16.0294,-0.499193,-2.71751,0.998253,0.253364,-0.327349 +259,1,16.0526,-0.499486,-2.72101,0.996789,0.24299,-0.334215 +260,1,16.0443,-0.49975,-2.71952,0.999164,0.251356,-0.328712 +261,1,16.0447,-0.499564,-2.71992,0.998091,0.248326,-0.329218 +262,1,16.03,-0.499303,-2.71685,0.998477,0.24991,-0.33632 +263,1,16.0535,-0.500089,-2.72149,0.996944,0.246973,-0.324316 +264,1,16.0552,-0.50014,-2.72201,0.995601,0.24546,-0.32268 +265,1,16.038,-0.499706,-2.71901,0.998242,0.246377,-0.332104 +266,1,16.028,-0.499102,-2.71714,0.998976,0.253382,-0.333216 +267,1,16.036,-0.498881,-2.71805,0.998141,0.248548,-0.332612 +268,1,16.0485,-0.500147,-2.72076,0.996139,0.245939,-0.328178 +269,1,16.0396,-0.499375,-2.71925,0.998115,0.246043,-0.334168 +270,1,16.0482,-0.498916,-2.72112,0.997438,0.243174,-0.335489 +271,1,16.0419,-0.499669,-2.71953,0.998883,0.248075,-0.334475 +272,1,16.0604,-0.499609,-2.72263,0.995823,0.241728,-0.327774 +273,1,16.0301,-0.499315,-2.71716,1.00078,0.260248,-0.328246 +274,1,16.0381,-0.4991,-2.71908,0.998327,0.253097,-0.32685 +275,1,16.0371,-0.499838,-2.71846,0.999133,0.248928,-0.33717 +276,1,16.0606,-0.500773,-2.7225,0.997507,0.253476,-0.319969 +277,1,16.029,-0.499371,-2.71726,1.001,0.253674,-0.337087 +278,1,16.0593,-0.500547,-2.72278,0.997859,0.249346,-0.321011 +279,1,16.0156,-0.498505,-2.71443,1.00071,0.254784,-0.340091 +280,1,16.0496,-0.499459,-2.72054,0.99745,0.24955,-0.326011 +281,1,16.0535,-0.500271,-2.72131,0.998675,0.250001,-0.326554 +282,1,16.0456,-0.499761,-2.72006,0.998847,0.247587,-0.330965 +283,1,16.0449,-0.499411,-2.71976,0.997743,0.250906,-0.328864 +284,1,16.0408,-0.500035,-2.71842,0.998903,0.252411,-0.33534 +285,1,16.0534,-0.500028,-2.72164,0.997319,0.247937,-0.324854 +286,1,16.0382,-0.499099,-2.7186,0.998296,0.246515,-0.336687 +287,1,16.0357,-0.499684,-2.71843,0.998416,0.255486,-0.32912 +288,1,16.0439,-0.499206,-2.71968,0.997187,0.248799,-0.3303 +289,1,16.0405,-0.500306,-2.71927,0.998235,0.250611,-0.332416 +290,1,16.0489,-0.498929,-2.72072,0.996098,0.2465,-0.32813 +291,1,16.0372,-0.498897,-2.71854,0.99883,0.248779,-0.333999 +292,1,16.0435,-0.499259,-2.71939,0.998558,0.252633,-0.329494 +293,1,16.0489,-0.499794,-2.71996,0.996426,0.239134,-0.338519 +294,1,16.0439,-0.4996,-2.71979,0.997768,0.252467,-0.327234 +295,1,16.0498,-0.499496,-2.72095,0.997337,0.245458,-0.328812 +296,1,16.0507,-0.500051,-2.72129,0.998177,0.246937,-0.327972 +297,1,16.0208,-0.499598,-2.71551,1.00175,0.263318,-0.334375 +298,1,16.0441,-0.499268,-2.71969,0.997937,0.253598,-0.327467 diff --git a/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_other.txt b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_other.txt new file mode 100644 index 0000000..4ebbd3e --- /dev/null +++ b/matlab/new_preprocess/predictions/apriltag_prediction/straight_front1-6/pose_other.txt @@ -0,0 +1,303 @@ +iter,id,x,y,z,r,p,y +0,1,0.499677,2.72677,16.1505,2.73256,0.0123019,-0.952741 +1,1,0.49984,2.72915,16.1706,2.73904,0.00828599,-0.953586 +2,1,0.50084,2.73137,16.1817,2.74669,0.00530056,-0.953963 +3,1,0.50012,2.73057,16.1691,2.74084,0.0131857,-0.952598 +4,1,0.499687,2.73022,16.1478,2.73205,0.0156805,-0.954149 +5,1,0.498472,2.72869,16.1438,2.72861,0.00878679,-0.953774 +6,1,0.499002,2.72807,16.1427,2.72856,0.0125922,-0.953137 +7,1,0.499587,2.72787,16.1438,2.72716,0.0128489,-0.952837 +8,1,0.499875,2.72653,16.1504,2.73435,0.0147593,-0.953111 +9,1,0.499126,2.72402,16.137,2.72693,0.0109655,-0.954579 +10,1,0.499028,2.72635,16.1389,2.72806,0.00634868,-0.953213 +11,1,0.500558,2.73016,16.1624,2.73913,0.0135642,-0.952924 +12,1,0.499888,2.73141,16.1576,2.73611,0.0127743,-0.952158 +13,1,0.499614,2.72812,16.1392,2.72584,0.0139619,-0.951627 +14,1,0.500024,2.72829,16.1497,2.7305,0.0173077,-0.95162 +15,1,0.50011,2.72653,16.1486,2.72925,0.0149935,-0.952515 +16,1,0.500503,2.73047,16.1689,2.73718,0.014458,-0.951775 +17,1,0.499378,2.72581,16.1422,2.72872,0.0130767,-0.953835 +18,1,0.498815,2.72596,16.1321,2.73065,0.00756564,-0.952313 +19,1,0.499801,2.73134,16.1608,2.73858,0.0145812,-0.953029 +20,1,0.499583,2.72614,16.1356,2.72465,0.0155728,-0.952412 +21,1,0.499932,2.73117,16.1639,2.7428,0.00802411,-0.953767 +22,1,0.499796,2.73109,16.1755,2.74164,0.00539208,-0.95346 +23,1,0.4998,2.72803,16.1555,2.73215,0.0109428,-0.953863 +24,1,0.499568,2.72671,16.1432,2.73066,0.0153987,-0.951052 +25,1,0.499213,2.72803,16.1471,2.73203,0.00833172,-0.953702 +26,1,0.499551,2.72907,16.1501,2.73267,0.0159967,-0.951271 +27,1,0.500196,2.73051,16.1613,2.73313,0.00890563,-0.954087 +28,1,0.499952,2.72687,16.1452,2.73204,0.0123493,-0.952092 +29,1,0.498625,2.72481,16.1334,2.72648,0.0106553,-0.952892 +30,1,0.500344,2.72871,16.1533,2.73266,0.00474933,-0.954821 +31,1,0.498956,2.72792,16.1489,2.73197,0.00935379,-0.952709 +32,1,0.499819,2.72906,16.1526,2.7373,0.0110344,-0.952762 +33,1,0.499619,2.7289,16.1508,2.7357,0.00769163,-0.95305 +34,1,0.49873,2.72663,16.1381,2.73249,0.00731421,-0.953485 +35,1,0.498892,2.72709,16.1421,2.73007,0.0111564,-0.952038 +36,1,0.499851,2.72685,16.1458,2.73167,0.0141058,-0.95269 +37,1,0.49898,2.72612,16.1402,2.73216,0.0147889,-0.951959 +38,1,0.499574,2.72772,16.144,2.72997,0.0153178,-0.951883 +39,1,0.499495,2.72908,16.151,2.73358,0.0108775,-0.952932 +40,1,0.498922,2.7267,16.1389,2.72995,0.0189648,-0.950767 +41,1,0.499422,2.72659,16.1434,2.73243,0.0132437,-0.952539 +42,1,0.499273,2.72694,16.1465,2.73227,0.0102034,-0.952881 +43,1,0.500526,2.73141,16.1714,2.73947,0.0120752,-0.953279 +44,1,0.499621,2.72759,16.1495,2.73093,0.0108178,-0.952721 +45,1,0.499954,2.72765,16.1484,2.73135,0.0126417,-0.952266 +46,1,0.499408,2.73185,16.1673,2.74392,0.00968375,-0.95271 +47,1,0.499523,2.72958,16.1547,2.73454,0.0139699,-0.95186 +48,1,0.499924,2.72845,16.1521,2.73395,0.0172124,-0.95173 +49,1,0.499335,2.728,16.1496,2.72991,0.016317,-0.952494 +50,1,0.500555,2.73039,16.1666,2.73739,0.0171521,-0.952098 +51,1,0.500084,2.72903,16.1575,2.7321,0.0146039,-0.953424 +52,1,0.499353,2.72817,16.148,2.73091,0.0127751,-0.952683 +53,1,0.498579,2.72302,16.1178,2.72102,0.0131016,-0.952822 +54,1,0.4995,2.72734,16.1442,2.73397,0.0142536,-0.95211 +55,1,0.499532,2.72764,16.1475,2.73168,0.0109105,-0.953589 +56,1,0.499548,2.72729,16.1448,2.7321,0.0152884,-0.951184 +57,1,0.499621,2.72819,16.1537,2.73062,0.0143591,-0.952643 +58,1,0.500861,2.7303,16.1639,2.73972,0.0114271,-0.952725 +59,1,0.499129,2.72626,16.1391,2.72898,0.0122447,-0.952756 +60,1,0.499604,2.72829,16.1504,2.73115,0.00885348,-0.952571 +61,1,0.499036,2.72781,16.1472,2.73322,0.0122142,-0.952048 +62,1,0.499248,2.72768,16.1482,2.73122,0.00476232,-0.954248 +63,1,0.499043,2.72315,16.1243,2.72585,0.0137294,-0.952113 +64,1,0.500131,2.72865,16.1543,2.734,0.00953745,-0.954534 +65,1,0.500401,2.73128,16.1713,2.74089,0.0118631,-0.952874 +66,1,0.500203,2.72969,16.1625,2.73712,0.0149271,-0.952348 +67,1,0.499219,2.72739,16.1446,2.73345,0.0149083,-0.952104 +68,1,0.500845,2.73122,16.1673,2.7367,0.015461,-0.952533 +69,1,0.499285,2.72735,16.1477,2.73116,0.0123503,-0.951907 +70,1,0.499427,2.72603,16.1379,2.72748,0.0137702,-0.951704 +71,1,0.498864,2.72485,16.1339,2.72848,0.0127233,-0.95289 +72,1,0.499635,2.72756,16.1498,2.73305,0.0147306,-0.952616 +73,1,0.499455,2.72727,16.1462,2.72988,0.0142015,-0.95087 +74,1,0.499163,2.7276,16.149,2.73317,0.010273,-0.95353 +75,1,0.499627,2.72732,16.1462,2.73188,0.0124641,-0.952889 +76,1,0.499875,2.72706,16.1441,2.73272,0.013968,-0.952694 +77,1,0.500044,2.72846,16.1554,2.73406,0.00965787,-0.952343 +78,1,0.499626,2.72727,16.1487,2.73039,0.0128431,-0.951961 +79,1,0.499037,2.72712,16.1452,2.7332,0.0128036,-0.952849 +80,1,0.499618,2.72707,16.1457,2.7327,0.0146151,-0.952844 +81,1,0.499601,2.72815,16.1515,2.73158,0.0116698,-0.952313 +82,1,0.499521,2.7281,16.1521,2.73414,0.00787189,-0.952076 +83,1,0.500307,2.72757,16.1484,2.73049,0.0156737,-0.953308 +84,1,0.498908,2.72617,16.1399,2.73195,0.0112251,-0.952603 +85,1,0.499594,2.7273,16.1509,2.735,0.013766,-0.953055 +86,1,0.499746,2.72809,16.1511,2.73524,0.0100523,-0.953933 +87,1,0.498856,2.72641,16.1422,2.73187,0.0070449,-0.952942 +88,1,0.500395,2.72913,16.159,2.73433,0.0148749,-0.953022 +89,1,0.499081,2.72818,16.1496,2.73688,0.00926321,-0.95385 +90,1,0.499256,2.72691,16.145,2.73516,0.0125055,-0.952378 +91,1,0.499195,2.72628,16.1415,2.73127,0.0136765,-0.952406 +92,1,0.498972,2.72451,16.1323,2.72733,0.0147171,-0.951851 +93,1,0.499103,2.72774,16.148,2.73241,0.0179584,-0.951798 +94,1,0.499275,2.72562,16.1387,2.7306,0.0144022,-0.952332 +95,1,0.499032,2.72419,16.1308,2.72607,0.0149849,-0.951887 +96,1,0.4998,2.72552,16.1389,2.7287,0.0128855,-0.952669 +97,1,0.499872,2.72689,16.1467,2.73327,0.0159654,-0.953115 +98,1,0.499361,2.72553,16.1418,2.72852,0.0114997,-0.953234 +99,1,0.499342,2.72802,16.1517,2.73481,0.0122971,-0.951992 +100,1,0.500449,2.72754,16.1491,2.73174,0.0113044,-0.954054 +101,1,0.499215,2.72734,16.151,2.73061,0.0140386,-0.952026 +102,1,0.499076,2.7265,16.1418,2.73279,0.0115108,-0.951641 +103,1,0.498949,2.72568,16.1397,2.73052,0.0115131,-0.952073 +104,1,0.500181,2.72805,16.151,2.73485,0.0122651,-0.953859 +105,1,0.499285,2.72691,16.1444,2.73109,0.00832344,-0.952751 +106,1,0.499478,2.72739,16.1489,2.73097,0.00858394,-0.952984 +107,1,0.499454,2.72798,16.1504,2.73476,0.00971612,-0.952867 +108,1,0.500276,2.72636,16.1465,2.73144,0.0147659,-0.95251 +109,1,0.499343,2.72773,16.1492,2.72962,0.0124618,-0.953028 +110,1,0.499744,2.72786,16.1484,2.73681,0.0145711,-0.952239 +111,1,0.499684,2.72577,16.1385,2.72931,0.00950023,-0.953999 +112,1,0.499498,2.72564,16.139,2.73144,0.0127628,-0.952636 +113,1,0.500022,2.7261,16.1412,2.7302,0.0136339,-0.952045 +114,1,0.498957,2.72476,16.1341,2.7255,0.0161332,-0.952889 +115,1,0.499357,2.72467,16.1321,2.72953,0.0135221,-0.95273 +116,1,0.499557,2.7266,16.1453,2.73295,0.011416,-0.953641 +117,1,0.498896,2.7246,16.1334,2.72807,0.00912263,-0.953857 +118,1,0.499457,2.72637,16.1437,2.7351,0.0105141,-0.952728 +119,1,0.499454,2.727,16.1438,2.73188,0.015248,-0.951432 +120,1,0.498962,2.72602,16.1409,2.73019,0.0106763,-0.952614 +121,1,0.499786,2.72889,16.1551,2.73637,0.00864548,-0.954157 +122,1,0.499521,2.72447,16.1337,2.72858,0.0150785,-0.952126 +123,1,0.499987,2.72916,16.1587,2.73643,0.0120366,-0.950594 +124,1,0.499265,2.72863,16.1538,2.73695,0.0134153,-0.951932 +125,1,0.498891,2.72528,16.1345,2.72758,0.0132981,-0.952507 +126,1,0.499584,2.72757,16.1507,2.73483,0.0138858,-0.952661 +127,1,0.500254,2.72715,16.1485,2.7304,0.0187644,-0.952122 +128,1,0.500374,2.72876,16.1572,2.73915,0.0139023,-0.952528 +129,1,0.499915,2.72824,16.1508,2.7353,0.0109315,-0.953172 +130,1,0.499082,2.72524,16.1371,2.72842,0.01682,-0.951571 +130,2,-11.0543,-4.8096,42.9606,1.40589,-3.02372,-3.06995 +131,1,0.49932,2.72895,16.1564,2.73846,0.0143472,-0.95219 +132,1,0.499921,2.7291,16.1596,2.73444,0.0115935,-0.952868 +133,1,0.498991,2.72472,16.1317,2.72689,0.0153714,-0.951927 +134,1,0.499718,2.72814,16.1529,2.73712,0.0144303,-0.951661 +135,1,0.499246,2.72622,16.1422,2.73145,0.0152427,-0.952769 +136,1,0.499021,2.72386,16.1292,2.72479,0.0121699,-0.952109 +137,1,0.499262,2.7267,16.1448,2.73224,0.0114021,-0.953305 +138,1,0.499012,2.72463,16.1357,2.72672,0.012399,-0.952835 +139,1,0.500223,2.72875,16.1581,2.73553,0.0103365,-0.953355 +140,1,0.499415,2.72927,16.1597,2.7353,0.00690042,-0.952657 +141,1,0.499276,2.7274,16.1474,2.73468,0.0143408,-0.95219 +142,1,0.499367,2.72704,16.1478,2.7338,0.0110721,-0.953035 +143,1,0.500215,2.7282,16.1527,2.73257,0.00779247,-0.953959 +144,1,0.499199,2.72625,16.1437,2.73096,0.0140601,-0.952959 +145,1,0.501504,2.73341,16.1866,2.74411,0.0106454,-0.952918 +146,1,0.498836,2.72303,16.1263,2.72537,0.0141461,-0.952941 +147,1,0.499206,2.72684,16.1482,2.73347,0.0122959,-0.953071 +148,1,0.499441,2.72794,16.1516,2.73479,0.00699813,-0.953453 +149,1,0.498816,2.72714,16.1468,2.73434,0.0151801,-0.951685 +150,1,0.499598,2.72821,16.1557,2.73502,0.00994535,-0.953446 +151,1,0.499159,2.72642,16.1411,2.73081,0.00953975,-0.95249 +152,1,0.500528,2.72994,16.163,2.73712,0.0116766,-0.953153 +153,1,0.500463,2.72736,16.1461,2.73199,0.0117307,-0.952923 +154,1,0.500919,2.73065,16.1675,2.74002,0.0182054,-0.952282 +155,1,0.499237,2.72605,16.1413,2.72872,0.0154427,-0.952792 +156,1,0.499801,2.72897,16.1605,2.73566,0.009162,-0.953016 +157,1,0.500075,2.72824,16.155,2.73375,0.011294,-0.95339 +158,1,0.499278,2.726,16.1432,2.7288,0.0124833,-0.952751 +159,1,0.499195,2.72626,16.1395,2.73233,0.00809551,-0.952278 +160,1,0.499298,2.72639,16.1445,2.73095,0.0130256,-0.953357 +161,1,0.49907,2.72629,16.1381,2.72949,0.0122546,-0.950917 +162,1,0.49988,2.72794,16.1531,2.7365,0.0135869,-0.952864 +163,1,0.499875,2.72491,16.1357,2.73069,0.0183306,-0.951912 +164,1,0.50029,2.72922,16.1612,2.7395,0.0171432,-0.951325 +165,1,0.500172,2.7298,16.1607,2.74057,0.0103965,-0.95399 +166,1,0.499376,2.72739,16.1488,2.73303,0.0141177,-0.951896 +167,1,0.499716,2.72762,16.1493,2.73686,0.0106518,-0.953436 +168,1,0.49957,2.7255,16.1387,2.73114,0.0110174,-0.953448 +169,1,0.500123,2.72709,16.149,2.73347,0.00985723,-0.953717 +170,1,0.499333,2.72758,16.147,2.73614,0.0158112,-0.952837 +171,1,0.499491,2.72496,16.138,2.73015,0.0160243,-0.951965 +172,1,0.499904,2.72835,16.1525,2.73588,0.0133688,-0.952897 +173,1,0.499646,2.72486,16.1375,2.72524,0.0131466,-0.95317 +174,1,0.500025,2.7294,16.1594,2.7393,0.0134947,-0.95216 +175,1,0.499659,2.72749,16.1479,2.73458,0.0131957,-0.952772 +176,1,0.499022,2.7297,16.1645,2.74007,0.0116502,-0.951595 +177,1,0.499382,2.72657,16.1449,2.73077,0.0104717,-0.954665 +178,1,0.500161,2.72903,16.1571,2.74039,0.0129216,-0.953498 +179,1,0.499706,2.72839,16.1541,2.73765,0.00961367,-0.953292 +180,1,0.498685,2.72414,16.1337,2.72661,0.0136263,-0.950912 +181,1,0.500498,2.73057,16.1631,2.73932,0.0148069,-0.952735 +182,1,0.499471,2.72796,16.1508,2.73515,0.0122561,-0.95214 +183,1,0.499691,2.72649,16.1425,2.7309,0.0147837,-0.952592 +184,1,0.500307,2.7301,16.1634,2.74034,0.0118158,-0.952922 +185,1,0.499063,2.7251,16.1381,2.72963,0.0126245,-0.952964 +186,1,0.499465,2.72622,16.1417,2.73065,0.0104544,-0.953222 +187,1,0.49918,2.72476,16.1367,2.7292,0.012994,-0.952859 +188,1,0.499823,2.72519,16.1396,2.72595,0.0134085,-0.953207 +189,1,0.500061,2.73033,16.1645,2.74209,0.00930378,-0.953964 +190,1,0.498308,2.72172,16.1171,2.71834,0.00742658,-0.954475 +191,1,0.499347,2.7279,16.1538,2.73335,0.0130353,-0.952384 +192,1,0.499856,2.72951,16.1563,2.73857,0.0110428,-0.952252 +193,1,0.498744,2.72498,16.1341,2.72456,0.00946555,-0.95223 +194,1,0.499328,2.72521,16.1376,2.72861,0.0117377,-0.952249 +195,1,0.499927,2.72869,16.1548,2.73302,0.00918804,-0.954183 +196,1,0.499651,2.72615,16.1445,2.73224,0.0155661,-0.952207 +197,1,0.499046,2.72402,16.1316,2.7259,0.0109208,-0.952884 +198,1,0.500084,2.72852,16.1575,2.73516,0.0147936,-0.952056 +199,1,0.499683,2.72905,16.1588,2.73732,0.0142069,-0.953347 +200,1,0.499293,2.72586,16.1407,2.7306,0.0161587,-0.952208 +201,1,0.499624,2.72713,16.1491,2.73095,0.014838,-0.952071 +202,1,0.499253,2.72702,16.1446,2.73085,0.0110162,-0.952921 +203,1,0.499707,2.72719,16.147,2.73307,0.0132546,-0.952847 +204,1,0.499478,2.72716,16.1464,2.73192,0.0117222,-0.953185 +205,1,0.499343,2.72657,16.1453,2.73221,0.0129074,-0.953567 +206,1,0.499906,2.7294,16.1602,2.73706,0.0144501,-0.952642 +207,1,0.499403,2.72681,16.1472,2.7334,0.014258,-0.952524 +208,1,0.500509,2.72926,16.1628,2.73852,0.0111215,-0.952276 +209,1,0.500378,2.72544,16.14,2.72904,0.0153814,-0.952511 +210,1,0.500358,2.72798,16.154,2.73223,0.0131991,-0.952438 +211,1,0.499331,2.72751,16.1492,2.73228,0.0119971,-0.952721 +212,1,0.500137,2.72914,16.1577,2.73571,0.0108973,-0.953463 +213,1,0.499564,2.72746,16.1497,2.73395,0.0127942,-0.952649 +214,1,0.499596,2.72795,16.1505,2.73266,0.0109571,-0.951777 +215,1,0.499197,2.72485,16.1341,2.7251,0.0120436,-0.953319 +216,1,0.499316,2.72695,16.1455,2.73259,0.0162455,-0.952326 +217,1,0.499354,2.72712,16.1478,2.73589,0.0156385,-0.952415 +218,1,0.500355,2.72937,16.16,2.73773,0.0116097,-0.953715 +219,1,0.498842,2.72524,16.1386,2.73058,0.01606,-0.952621 +220,1,0.499546,2.72628,16.1436,2.73489,0.0116518,-0.952696 +221,1,0.499721,2.72787,16.153,2.73586,0.0112486,-0.95274 +222,1,0.499888,2.73028,16.1656,2.73779,0.00637991,-0.95317 +223,1,0.498821,2.72417,16.1313,2.72912,0.0118516,-0.952772 +224,1,0.499634,2.72459,16.1336,2.72471,0.0148899,-0.952486 +225,1,0.499879,2.72852,16.1546,2.73546,0.00717379,-0.95334 +226,1,0.499211,2.72559,16.1353,2.72784,0.0088212,-0.954847 +227,1,0.499159,2.72475,16.1351,2.72807,0.0124924,-0.952513 +228,1,0.499914,2.72845,16.1554,2.73712,0.0118139,-0.953628 +229,1,0.499719,2.7299,16.1614,2.73915,0.00860498,-0.95333 +230,1,0.499189,2.72348,16.1284,2.72335,0.0114399,-0.952199 +230,14,1.49189,-1.2712,2.6013,1.57318,-0.735569,-1.64644 +231,1,0.500367,2.72884,16.1575,2.73439,0.0184271,-0.952682 +232,1,0.499543,2.72805,16.1529,2.73627,0.00767137,-0.953604 +233,1,0.499303,2.72453,16.1334,2.72883,0.0145494,-0.952223 +234,1,0.499404,2.72441,16.1333,2.72558,0.0139228,-0.952689 +235,1,0.500067,2.72874,16.1545,2.73321,0.0126327,-0.952085 +236,1,0.499941,2.7282,16.1533,2.73635,0.0134677,-0.952363 +237,1,0.500666,2.73019,16.1656,2.73686,0.0110191,-0.953304 +238,1,0.499647,2.72505,16.1388,2.7294,0.0113506,-0.952971 +239,1,0.499971,2.72969,16.1626,2.73459,0.0059347,-0.954741 +240,1,0.499116,2.72664,16.147,2.73631,0.0111681,-0.952465 +240,23,7.01597,-21.8705,77.5228,1.14747,-2.29555,-2.79605 +241,1,0.499888,2.72878,16.1564,2.73763,0.00972205,-0.953679 +242,1,0.49897,2.72271,16.1239,2.72273,0.0147128,-0.953451 +243,1,0.49958,2.72608,16.1419,2.73306,0.0190422,-0.951914 +244,1,0.499602,2.72552,16.1391,2.72807,0.0141102,-0.952238 +245,1,0.499793,2.72631,16.1431,2.73338,0.0113465,-0.954102 +246,1,0.499645,2.72698,16.1456,2.73173,0.00899785,-0.952968 +247,1,0.500026,2.72786,16.151,2.73269,0.0111821,-0.953317 +248,1,0.500183,2.72842,16.1548,2.73387,0.0147678,-0.95242 +249,1,0.499708,2.72577,16.1422,2.72924,0.014117,-0.952242 +250,1,0.49944,2.72832,16.1532,2.73484,0.00778356,-0.954791 +251,1,0.500159,2.72756,16.1513,2.73627,0.0159046,-0.952021 +252,1,0.500513,2.73049,16.1677,2.74319,0.0121369,-0.953412 +253,1,0.499197,2.72816,16.1512,2.73411,0.012572,-0.952598 +254,1,0.499549,2.7246,16.1339,2.72415,0.0139308,-0.952099 +255,1,0.499523,2.72922,16.1578,2.73682,0.010463,-0.952435 +256,1,0.499206,2.72673,16.1423,2.73373,0.0123213,-0.953096 +257,1,0.499558,2.72835,16.1543,2.73469,0.00934132,-0.954853 +258,1,0.499013,2.72438,16.1304,2.72949,0.0114858,-0.952534 +259,1,0.499854,2.72969,16.1633,2.73692,0.00909782,-0.953269 +260,1,0.499969,2.72847,16.1567,2.73591,0.0113174,-0.953733 +261,1,0.49989,2.72891,16.1572,2.73815,0.0125765,-0.953229 +262,1,0.499644,2.72573,16.1417,2.73145,0.0111798,-0.952798 +263,1,0.499817,2.72703,16.147,2.73264,0.0135566,-0.952831 +264,1,0.500185,2.72957,16.1599,2.74046,0.011566,-0.952206 +265,1,0.500193,2.7285,16.1531,2.73898,0.0126002,-0.953588 +266,1,0.499094,2.72464,16.1323,2.72717,0.0111404,-0.952748 +267,1,0.499178,2.72685,16.1474,2.73478,0.0109864,-0.953137 +268,1,0.500235,2.72793,16.1509,2.73551,0.0136008,-0.951932 +269,1,0.499757,2.72827,16.1521,2.73592,0.0101239,-0.953684 +270,1,0.499261,2.72972,16.1584,2.73547,0.00848396,-0.953827 +271,1,0.499981,2.72862,16.1549,2.73413,0.00837286,-0.954117 +272,1,0.500153,2.73228,16.1765,2.74589,0.0119996,-0.95278 +273,1,0.499484,2.72625,16.1434,2.73087,0.0159911,-0.952632 +274,1,0.499143,2.72661,16.1426,2.73275,0.0163679,-0.952103 +275,1,0.500073,2.7267,16.1453,2.72948,0.0104151,-0.953712 +276,1,0.501001,2.73129,16.1722,2.74135,0.0188675,-0.951503 +277,1,0.499694,2.72592,16.1395,2.72821,0.015535,-0.953726 +278,1,0.500537,2.7299,16.1616,2.7384,0.0172352,-0.952956 +279,1,0.498622,2.72225,16.1216,2.72238,0.0118837,-0.953385 +280,1,0.49968,2.72911,16.1599,2.73851,0.0136951,-0.952468 +281,1,0.50057,2.73039,16.1666,2.73923,0.0137701,-0.953475 +282,1,0.50003,2.72893,16.1575,2.73655,0.00971098,-0.954335 +283,1,0.499602,2.72835,16.1553,2.73526,0.0117583,-0.952415 +284,1,0.500157,2.72598,16.1454,2.72706,0.0141488,-0.952359 +285,1,0.500227,2.73008,16.163,2.73996,0.0131116,-0.952894 +286,1,0.499157,2.7254,16.1385,2.72762,0.0114409,-0.953448 +287,1,0.499715,2.72658,16.1437,2.73046,0.0118061,-0.951954 +288,1,0.499614,2.72931,16.1599,2.73872,0.0108233,-0.95234 +289,1,0.500625,2.72828,16.1531,2.73421,0.0120034,-0.952619 +290,1,0.498976,2.72768,16.1502,2.73462,0.0139585,-0.951724 +291,1,0.499129,2.72712,16.1475,2.73271,0.00944154,-0.953824 +292,1,0.499132,2.72603,16.1431,2.72824,0.0137827,-0.952544 +293,1,0.500281,2.729,16.1614,2.737,0.00588496,-0.953885 +294,1,0.499652,2.72767,16.1504,2.73342,0.0132454,-0.952047 +295,1,0.49968,2.72899,16.1571,2.73747,0.0112113,-0.95341 +296,1,0.500521,2.73129,16.1688,2.74275,0.0110341,-0.953897 +297,1,0.499751,2.72434,16.1326,2.72374,0.0163196,-0.952225 +298,1,0.499623,2.72943,16.1608,2.73793,0.013448,-0.951844 diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-1/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-1/tag_size1.220000pose.txt new file mode 100644 index 0000000..1991475 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-1/tag_size1.220000pose.txt @@ -0,0 +1,9 @@ +iter, id, rot_num, x, y, z, r, p, y +3,0,0,2.09652,-0.0856525,-0.0254915,1.94641,-2.78544,0.36819, +45,0,0,2.09589,-0.0846576,-0.0248372,1.88713,-2.76395,0.345615, +53,0,0,2.12569,-0.117007,0.0128198,1.87624,-2.76738,0.329927, +82,0,0,2.10358,-0.110104,-0.0394719,1.90959,-2.7832,0.369343, +95,0,0,2.09524,-0.083993,-0.0266805,1.92143,-2.77593,0.360712, +111,0,0,2.0976,-0.0925235,-0.0377738,1.92581,-2.78219,0.369077, +123,0,0,2.11099,-0.10515,-0.0186316,1.93296,-2.78811,0.364397, +125,0,0,2.11188,-0.10644,-0.0180326,1.90993,-2.7806,0.356103, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-2/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-2/tag_size1.220000pose.txt new file mode 100644 index 0000000..4cf6fb0 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-2/tag_size1.220000pose.txt @@ -0,0 +1,3 @@ +iter, id, rot_num, x, y, z, r, p, y +28,0,0,4.23099,-0.243739,-0.0899895,2.54435,-3.09298,0.499938, +37,0,0,4.23102,-0.245862,-0.0913841,2.33689,-2.98344,0.478891, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-3/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-3/tag_size1.220000pose.txt new file mode 100644 index 0000000..09f21ca --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-3/tag_size1.220000pose.txt @@ -0,0 +1,72 @@ +iter, id, rot_num, x, y, z, r, p, y +0,0,0,6.41546,-0.421956,-0.154646,2.55278,-3.12071,0.475491, +1,0,0,6.4154,-0.414479,-0.143677,2.57027,-3.12787,0.474526, +2,0,0,6.41421,-0.417599,-0.154408,2.55058,-3.11903,0.474993, +3,0,0,6.41668,-0.425288,-0.157511,2.56149,-3.12829,0.474506, +4,0,0,6.41398,-0.416341,-0.152281,2.54684,-3.11905,0.473004, +6,0,0,6.41637,-0.423404,-0.156608,2.55752,-3.1237,0.474735, +7,0,0,6.4164,-0.42121,-0.152109,2.55855,-3.12334,0.475354, +11,0,0,6.4132,-0.416414,-0.153703,2.5483,-3.11836,0.47443, +14,0,0,6.41393,-0.419439,-0.156483,2.57755,-3.1329,0.475175, +17,0,0,6.41555,-0.422013,-0.155142,2.55394,-3.12347,0.476135, +18,0,0,6.41545,-0.424894,-0.158984,2.56259,-3.12373,0.477063, +21,0,0,6.41701,-0.423091,-0.149041,2.54918,-3.11743,0.474579, +22,0,0,6.41528,-0.421264,-0.153944,2.52173,-3.10465,0.474345, +23,0,0,6.4145,-0.417765,-0.152004,2.55117,-3.12229,0.474528, +25,0,0,6.4153,-0.418986,-0.153561,2.56153,-3.12573,0.475611, +26,0,0,6.4142,-0.417784,-0.154345,2.56811,-3.12818,0.47426, +28,0,0,6.41734,-0.427004,-0.159752,2.55778,-3.12538,0.474343, +31,0,0,6.41619,-0.422295,-0.153696,2.53274,-3.11098,0.473823, +35,0,0,6.41599,-0.422053,-0.15512,2.563,-3.12572,0.4745, +36,0,0,6.41601,-0.421093,-0.153782,2.55705,-3.12313,0.475005, +37,0,0,6.41463,-0.421595,-0.160221,2.55935,-3.12737,0.474184, +38,0,0,6.41607,-0.422702,-0.155049,2.55998,-3.12497,0.475584, +39,0,0,6.41623,-0.422442,-0.156466,2.55975,-3.12544,0.475497, +41,0,0,6.41617,-0.422471,-0.155511,2.56401,-3.12663,0.475594, +44,0,0,6.41583,-0.421332,-0.154182,2.52627,-3.10651,0.474264, +45,0,0,6.4136,-0.416492,-0.1547,2.55549,-3.12205,0.475783, +48,0,0,6.41579,-0.42623,-0.16004,2.5733,-3.13491,0.47584, +50,0,0,6.41436,-0.422191,-0.159051,2.56265,-3.12686,0.475287, +55,0,0,6.41585,-0.423333,-0.15643,2.57174,-3.12955,0.476517, +56,0,0,6.41437,-0.416684,-0.153042,2.55272,-3.12096,0.475938, +57,0,0,6.41651,-0.420201,-0.152445,2.5395,-3.11547,0.47564, +59,0,0,6.41592,-0.422167,-0.155189,2.55558,-3.1225,0.476194, +62,0,0,6.4155,-0.421087,-0.154794,2.53997,-3.11522,0.474468, +63,0,0,6.41479,-0.418333,-0.153152,2.55155,-3.11936,0.476182, +65,0,0,6.4156,-0.426887,-0.160203,2.54846,-3.12042,0.475685, +70,0,0,6.41432,-0.418219,-0.154316,2.56434,-3.12761,0.475798, +71,0,0,6.41512,-0.420228,-0.155564,2.56321,-3.12642,0.475182, +72,0,0,6.4159,-0.423132,-0.155396,2.56121,-3.12627,0.475393, +74,0,0,6.41439,-0.419798,-0.156969,2.543,-3.11678,0.475694, +75,0,0,6.41531,-0.4177,-0.152361,2.55154,-3.12347,0.474718, +76,0,0,6.41531,-0.422788,-0.155944,2.55316,-3.12232,0.476533, +77,0,0,6.41534,-0.423003,-0.157659,2.57271,-3.13003,0.475986, +78,0,0,6.41572,-0.425716,-0.157354,2.55454,-3.12515,0.475156, +79,0,0,6.41553,-0.425033,-0.160996,2.557,-3.12553,0.475472, +81,0,0,6.41524,-0.420477,-0.156394,2.54025,-3.11451,0.475177, +82,0,0,6.41506,-0.420884,-0.15549,2.54705,-3.11916,0.476149, +83,0,0,6.41453,-0.422256,-0.158327,2.56277,-3.12811,0.475671, +84,0,0,6.41529,-0.418531,-0.153953,2.57214,-3.12968,0.475181, +85,0,0,6.41472,-0.422132,-0.1583,2.56113,-3.12751,0.47477, +87,0,0,6.41517,-0.419506,-0.154373,2.55193,-3.12057,0.475206, +88,0,0,6.41691,-0.422628,-0.154316,2.55194,-3.12152,0.476797, +91,0,0,6.41595,-0.425582,-0.158804,2.57193,-3.1349,0.475272, +93,0,0,6.41638,-0.418857,-0.152482,2.55189,-3.12072,0.475166, +95,0,0,6.41556,-0.425049,-0.158589,2.57152,-3.13428,0.475769, +97,0,0,6.41481,-0.419357,-0.156582,2.56559,-3.12876,0.476431, +99,0,0,6.4154,-0.425161,-0.159656,2.55593,-3.12581,0.475433, +103,0,0,6.41587,-0.423748,-0.155542,2.57585,-3.13043,0.476461, +104,0,0,6.41578,-0.423938,-0.160836,2.57645,-3.1358,0.475696, +112,0,0,6.41452,-0.418083,-0.154215,2.555,-3.12277,0.475982, +113,0,0,6.41517,-0.41986,-0.157181,2.55803,-3.12538,0.475763, +114,0,0,6.41495,-0.420602,-0.155158,2.55468,-3.12284,0.4761, +117,0,0,6.41634,-0.419578,-0.152872,2.54666,-3.11669,0.476418, +119,0,0,6.41649,-0.425837,-0.158112,2.55636,-3.12593,0.474728, +121,0,0,6.4147,-0.421781,-0.158886,2.56282,-3.12893,0.476959, +122,0,0,6.41506,-0.419241,-0.154939,2.52639,-3.10864,0.474592, +124,0,0,6.41753,-0.427585,-0.158468,2.5551,-3.12445,0.475684, +125,0,0,6.41595,-0.425301,-0.157981,2.55466,-3.12606,0.475192, +126,0,0,6.4161,-0.42412,-0.159695,2.57022,-3.13281,0.47489, +127,0,0,6.41614,-0.424632,-0.153722,2.55242,-3.12194,0.476538, +128,0,0,6.41644,-0.426686,-0.159779,2.55924,-3.12964,0.475962, +129,0,0,6.41439,-0.41776,-0.153185,2.55373,-3.12189,0.474732, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-4/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-4/tag_size1.220000pose.txt new file mode 100644 index 0000000..7e4443c --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-4/tag_size1.220000pose.txt @@ -0,0 +1,10 @@ +iter, id, rot_num, x, y, z, r, p, y +7,0,0,8.37516,-0.436765,0.0435031,2.48578,-3.03873,0.447353, +21,0,0,8.37954,-0.446027,0.0377514,2.48664,-3.03794,0.449627, +24,0,0,8.37719,-0.436982,0.0327149,2.45514,-3.0225,0.447908, +31,0,0,8.37816,-0.442571,0.0355813,2.4811,-3.0344,0.447899, +81,0,0,8.3771,-0.444053,0.0384449,2.47779,-3.03245,0.448016, +82,0,0,8.37978,-0.441878,0.029568,2.46902,-3.02815,0.449897, +85,0,0,8.38543,-0.404682,0.1525,2.55345,-3.05612,0.450286, +118,0,0,8.3765,-0.442043,0.0314958,2.47727,-3.03564,0.452031, +124,0,0,8.38115,-0.448535,0.0347173,2.49698,-3.04323,0.451511, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-5/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-5/tag_size1.220000pose.txt new file mode 100644 index 0000000..b9479ca --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-5/tag_size1.220000pose.txt @@ -0,0 +1,77 @@ +iter, id, rot_num, x, y, z, r, p, y +3,0,0,10.3669,-0.558968,-0.0858508,2.52349,-3.10748,0.442921, +4,0,0,10.372,-0.566438,-0.0925472,2.52473,-3.1076,0.441859, +5,0,0,10.3659,-0.556546,-0.103011,2.54875,-3.1197,0.442387, +7,0,0,10.3694,-0.562249,-0.0941649,2.52388,-3.10812,0.441952, +8,0,0,10.369,-0.562962,-0.106781,2.55735,-3.12376,0.44484, +10,0,0,10.3704,-0.562578,-0.0927847,2.54276,-3.11553,0.441435, +13,0,0,10.3702,-0.557324,-0.106153,2.5402,-3.1151,0.443504, +17,0,0,10.369,-0.563154,-0.0964472,2.54467,-3.11616,0.442599, +19,0,0,10.368,-0.562165,-0.0998153,2.54806,-3.11941,0.441753, +20,0,0,10.3715,-0.563125,-0.0910838,2.53011,-3.10994,0.442659, +25,0,0,10.3695,-0.560745,-0.0996903,2.52584,-3.10788,0.441858, +26,0,0,10.368,-0.565066,-0.10091,2.54221,-3.11474,0.443517, +27,0,0,10.369,-0.562888,-0.0997973,2.55637,-3.12233,0.444371, +30,0,0,10.3704,-0.56102,-0.0912203,2.53172,-3.11149,0.440873, +31,0,0,10.3686,-0.553901,-0.106444,2.55676,-3.12306,0.443929, +33,0,0,10.3709,-0.564797,-0.114351,2.53771,-3.1133,0.44333, +34,0,0,10.3712,-0.569507,-0.0938085,2.54963,-3.11994,0.442567, +35,0,0,10.3681,-0.563117,-0.101411,2.5623,-3.12629,0.442567, +36,0,0,10.3687,-0.562057,-0.0983382,2.55431,-3.1222,0.442872, +38,0,0,10.3687,-0.560978,-0.0960631,2.48606,-3.09046,0.439507, +42,0,0,10.3684,-0.556895,-0.0942151,2.54405,-3.11494,0.44226, +43,0,0,10.3704,-0.563078,-0.0935482,2.52801,-3.10881,0.443323, +44,0,0,10.3703,-0.564321,-0.101635,2.53365,-3.11018,0.442109, +45,0,0,10.3738,-0.568261,-0.0861776,2.56175,-3.12356,0.443893, +46,0,0,10.3687,-0.565956,-0.100221,2.54482,-3.11844,0.443548, +47,0,0,10.3663,-0.557273,-0.0968707,2.55134,-3.11929,0.443697, +48,0,0,10.3674,-0.555399,-0.110358,2.55938,-3.12562,0.444529, +49,0,0,10.369,-0.563406,-0.0936107,2.5331,-3.1133,0.442413, +50,0,0,10.3691,-0.566716,-0.102195,2.5407,-3.11507,0.443495, +51,0,0,10.3679,-0.561654,-0.100216,2.54716,-3.11873,0.442439, +53,0,0,10.3695,-0.562371,-0.0972284,2.53233,-3.10976,0.442281, +54,0,0,10.3651,-0.553052,-0.112562,2.53317,-3.11154,0.441383, +57,0,0,10.3676,-0.558086,-0.105064,2.5381,-3.11321,0.442009, +58,0,0,10.367,-0.55844,-0.100328,2.554,-3.12368,0.441933, +59,0,0,10.3684,-0.558846,-0.0959216,2.5469,-3.11671,0.442992, +60,0,0,10.3696,-0.561528,-0.0971074,2.5622,-3.12472,0.444332, +63,0,0,10.3694,-0.560603,-0.0936144,2.53941,-3.11381,0.442946, +64,0,0,10.3727,-0.565076,-0.0983058,2.5354,-3.11358,0.444933, +65,0,0,10.3693,-0.56364,-0.0985366,2.55209,-3.12133,0.443981, +66,0,0,10.3699,-0.564918,-0.108906,2.52904,-3.10901,0.44615, +69,0,0,10.3687,-0.561644,-0.0938085,2.54283,-3.11658,0.442333, +70,0,0,10.3693,-0.565157,-0.108644,2.56531,-3.12631,0.443761, +71,0,0,10.3689,-0.561538,-0.0974055,2.54686,-3.11843,0.441896, +72,0,0,10.3657,-0.558059,-0.0924628,2.51491,-3.10181,0.442253, +74,0,0,10.3686,-0.558192,-0.110657,2.55046,-3.11843,0.443422, +76,0,0,10.3679,-0.563168,-0.103082,2.56694,-3.12799,0.444334, +78,0,0,10.3689,-0.563465,-0.0956449,2.5082,-3.09904,0.442749, +79,0,0,10.3698,-0.561462,-0.0919809,2.53411,-3.11086,0.443027, +80,0,0,10.3706,-0.56964,-0.0987908,2.54659,-3.11831,0.442147, +82,0,0,10.3672,-0.557949,-0.104503,2.53911,-3.11312,0.44324, +83,0,0,10.3678,-0.562987,-0.099626,2.58067,-3.13309,0.442663, +84,0,0,10.3688,-0.560125,-0.112518,2.54678,-3.11689,0.447107, +85,0,0,10.3706,-0.564403,-0.111329,2.55102,-3.12161,0.444549, +86,0,0,10.3772,-0.55806,-0.0742673,2.51777,-3.10677,0.438661, +87,0,0,10.3704,-0.560202,-0.103602,2.54251,-3.11705,0.442033, +89,0,0,10.3683,-0.558637,-0.112748,2.54439,-3.1166,0.445334, +90,0,0,10.3711,-0.565787,-0.0956946,2.54164,-3.11382,0.442466, +92,0,0,10.3668,-0.559334,-0.0958155,2.54324,-3.11748,0.440751, +93,0,0,10.3677,-0.554693,-0.0978502,2.53247,-3.11202,0.441659, +95,0,0,10.3695,-0.565935,-0.0997174,2.55004,-3.12065,0.442988, +96,0,0,10.3698,-0.566799,-0.106054,2.52803,-3.10912,0.444196, +97,0,0,10.3695,-0.565955,-0.0976997,2.53524,-3.11231,0.443098, +100,0,0,10.3685,-0.561184,-0.0971478,2.54277,-3.11673,0.442403, +101,0,0,10.3697,-0.561255,-0.108489,2.54736,-3.11822,0.444082, +109,0,0,10.3695,-0.558013,-0.10003,2.54135,-3.11552,0.442668, +110,0,0,10.3677,-0.563004,-0.100703,2.53941,-3.11421,0.444349, +111,0,0,10.3712,-0.565594,-0.0961757,2.53367,-3.11191,0.442412, +113,0,0,10.3729,-0.571222,-0.0988167,2.5304,-3.10961,0.442556, +116,0,0,10.3674,-0.558583,-0.0963191,2.53815,-3.11504,0.441335, +117,0,0,10.3672,-0.563146,-0.103801,2.52489,-3.10905,0.443072, +120,0,0,10.3723,-0.564564,-0.0879132,2.5483,-3.11685,0.443841, +121,0,0,10.3689,-0.56088,-0.102944,2.54044,-3.11663,0.443856, +122,0,0,10.3717,-0.567446,-0.0933542,2.5468,-3.11654,0.44226, +124,0,0,10.3742,-0.565771,-0.102267,2.5611,-3.1245,0.444591, +125,0,0,10.3674,-0.559946,-0.0945205,2.52802,-3.10944,0.442402, +127,0,0,10.3689,-0.560135,-0.0919839,2.51798,-3.10498,0.441791, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/ccw1-6/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-6/tag_size1.220000pose.txt new file mode 100644 index 0000000..11cb254 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/ccw1-6/tag_size1.220000pose.txt @@ -0,0 +1,73 @@ +iter, id, rot_num, x, y, z, r, p, y +2,0,0,12.1045,-0.426785,-0.36928,2.52467,-3.12166,0.46832, +3,0,0,12.1113,-0.432046,-0.354944,2.55361,-3.13703,0.467076, +4,0,0,12.1063,-0.426916,-0.364762,2.54166,-3.13139,0.466457, +9,0,0,12.1065,-0.421271,-0.359707,2.55272,-3.13682,0.467448, +12,0,0,12.1105,-0.426028,-0.354914,2.55748,-3.14001,0.467827, +13,0,0,12.1057,-0.425337,-0.364822,2.55292,-3.13867,0.468026, +15,0,0,12.1099,-0.427253,-0.352293,2.56027,-3.13845,0.46782, +16,0,0,12.1077,-0.430277,-0.363057,2.51989,-3.12131,0.467087, +17,0,0,12.1088,-0.42129,-0.352157,2.54852,-3.13506,0.467364, +18,0,0,12.108,-0.428714,-0.362001,2.55724,-3.13835,0.468012, +19,0,0,12.1058,-0.425515,-0.363968,2.56098,3.14095,0.466753, +24,0,0,12.1077,-0.42244,-0.350184,2.56353,3.14129,0.467574, +26,0,0,12.1058,-0.422063,-0.359278,2.55605,-3.13827,0.470074, +28,0,0,12.1075,-0.434183,-0.367971,2.53423,-3.13033,0.46692, +30,0,0,12.108,-0.43141,-0.364652,2.56456,3.14097,0.468115, +32,0,0,12.1076,-0.426336,-0.362103,2.52083,-3.12168,0.46635, +33,0,0,12.1058,-0.421387,-0.361657,2.55861,-3.13987,0.468301, +34,0,0,12.1063,-0.420012,-0.360515,2.53483,-3.12681,0.46704, +35,0,0,12.1084,-0.421526,-0.353188,2.58606,3.1316,0.467488, +40,0,0,12.108,-0.418236,-0.349808,2.5649,3.14076,0.468713, +43,0,0,12.1109,-0.42646,-0.353629,2.55266,-3.13611,0.467823, +45,0,0,12.107,-0.428799,-0.365218,2.52605,-3.12436,0.467856, +46,0,0,12.1061,-0.429482,-0.369345,2.5362,-3.13004,0.468471, +48,0,0,12.1143,-0.432588,-0.356606,2.54514,-3.13457,0.467145, +51,0,0,12.1079,-0.423101,-0.360163,2.55654,-3.1407,0.467864, +54,0,0,12.1059,-0.425155,-0.36268,2.54927,-3.13539,0.466517, +56,0,0,12.1037,-0.420521,-0.36813,2.5554,-3.13892,0.467786, +57,0,0,12.1094,-0.424653,-0.351239,2.54179,-3.13071,0.467081, +58,0,0,12.1122,-0.435498,-0.369391,2.54506,-3.13556,0.467566, +59,0,0,12.1087,-0.418512,-0.349072,2.53863,-3.12914,0.466981, +60,0,0,12.1053,-0.425398,-0.36382,2.54217,-3.1319,0.466738, +62,0,0,12.1064,-0.422859,-0.357768,2.54326,-3.13461,0.467265, +63,0,0,12.1109,-0.42703,-0.353838,2.55149,-3.13605,0.46568, +64,0,0,12.1035,-0.425444,-0.371493,2.55686,-3.14086,0.465893, +65,0,0,12.1107,-0.418976,-0.345887,2.55981,-3.1385,0.467732, +66,0,0,12.1093,-0.432272,-0.362468,2.55587,-3.1388,0.468101, +67,0,0,12.1086,-0.431407,-0.363183,2.52723,-3.12484,0.46703, +69,0,0,12.1102,-0.433687,-0.366595,2.5511,-3.13716,0.467906, +70,0,0,12.1119,-0.425814,-0.346914,2.5514,-3.13626,0.468307, +71,0,0,12.1023,-0.414541,-0.361074,2.58344,3.12943,0.466149, +73,0,0,12.1048,-0.419802,-0.361446,2.55444,-3.13757,0.467952, +75,0,0,12.1076,-0.429862,-0.36075,2.52059,-3.12263,0.465169, +77,0,0,12.1069,-0.424156,-0.359379,2.53053,-3.12482,0.468136, +78,0,0,12.108,-0.43111,-0.362487,2.51014,-3.11788,0.466519, +79,0,0,12.1085,-0.425802,-0.356897,2.53136,-3.12592,0.465626, +80,0,0,12.1069,-0.430813,-0.366801,2.53119,-3.12912,0.466842, +81,0,0,12.1077,-0.425709,-0.35901,2.53101,-3.12619,0.468476, +83,0,0,12.1071,-0.426429,-0.362547,2.57959,3.13245,0.467602, +85,0,0,12.1052,-0.426519,-0.369503,2.5533,-3.13882,0.46712, +87,0,0,12.1085,-0.426379,-0.361011,2.52856,-3.12254,0.467461, +88,0,0,12.1072,-0.428771,-0.3651,2.52195,-3.12319,0.467978, +89,0,0,12.1074,-0.416492,-0.349869,2.53672,-3.12742,0.466579, +91,0,0,12.1064,-0.423472,-0.359186,2.56137,-3.14141,0.4683, +93,0,0,12.1099,-0.424793,-0.350089,2.54597,-3.13273,0.468395, +94,0,0,12.1101,-0.430579,-0.363296,2.56982,3.13845,0.46889, +98,0,0,12.1111,-0.426233,-0.352239,2.57126,3.1387,0.467616, +99,0,0,12.1071,-0.420433,-0.35917,2.54673,-3.13324,0.468258, +100,0,0,12.107,-0.428495,-0.361131,2.55793,-3.14143,0.467734, +101,0,0,12.1084,-0.427379,-0.360822,2.5274,-3.12321,0.467536, +103,0,0,12.117,-0.433028,-0.338992,2.55674,-3.139,0.466687, +106,0,0,12.1098,-0.422453,-0.349254,2.54013,-3.12945,0.466644, +112,0,0,12.1068,-0.427332,-0.365045,2.53568,-3.12991,0.465875, +114,0,0,12.107,-0.427906,-0.361826,2.51658,-3.11893,0.465846, +115,0,0,12.1084,-0.423633,-0.351509,2.56516,3.13947,0.465845, +116,0,0,12.1074,-0.429225,-0.36226,2.52137,-3.1222,0.466279, +117,0,0,12.1056,-0.427476,-0.368921,2.55483,-3.13904,0.467808, +123,0,0,12.1106,-0.423559,-0.346523,2.54252,-3.12984,0.467263, +125,0,0,12.1073,-0.425385,-0.362393,2.53633,-3.12871,0.466457, +126,0,0,12.1109,-0.436432,-0.362518,2.50868,-3.11548,0.466518, +127,0,0,12.1093,-0.420486,-0.346886,2.55559,-3.13712,0.467091, +128,0,0,12.1117,-0.440771,-0.372124,2.53792,-3.13195,0.467265, +130,0,0,12.1034,-0.420817,-0.368882,2.54444,-3.13222,0.46728, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-2/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-2/tag_size1.220000pose.txt new file mode 100644 index 0000000..1269e60 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-2/tag_size1.220000pose.txt @@ -0,0 +1,20 @@ +iter, id, rot_num, x, y, z, r, p, y +3,0,0,4.08842,-0.13149,-0.0748762,2.47029,2.94519,0.168235, +19,0,0,4.0887,-0.133963,-0.0751436,2.47373,2.94353,0.167566, +23,0,0,4.08847,-0.13445,-0.0761139,2.47536,2.9432,0.168999, +36,0,0,4.08724,-0.135173,-0.0746402,2.48501,2.94267,0.169683, +39,0,0,4.0883,-0.135242,-0.0754641,2.48332,2.94136,0.167111, +47,0,0,4.08832,-0.132867,-0.0765195,2.41156,2.95466,0.17965, +53,0,0,4.08876,-0.134327,-0.0754573,2.46648,2.94409,0.169277, +60,0,0,4.08847,-0.133943,-0.0758913,2.47527,2.94246,0.166879, +83,0,0,4.08861,-0.13166,-0.0759179,2.48656,2.94123,0.165681, +87,0,0,4.08757,-0.139082,-0.0764977,2.48217,2.9429,0.165637, +90,0,0,4.08913,-0.145186,-0.0725982,2.46206,2.94583,0.169681, +93,0,0,4.08777,-0.146186,-0.0787705,2.47926,2.94283,0.166789, +95,0,0,4.08606,-0.144222,-0.0812156,2.48531,2.94286,0.1652, +110,0,0,4.08834,-0.134273,-0.0749027,2.49679,2.93958,0.162835, +115,0,0,4.08774,-0.133821,-0.0767404,2.40749,2.9549,0.180602, +116,0,0,4.08831,-0.135753,-0.0743986,2.48743,2.94177,0.166449, +119,0,0,4.08834,-0.133875,-0.0748651,2.48535,2.94217,0.165165, +122,0,0,4.08832,-0.135633,-0.0747093,2.48592,2.94321,0.166685, +130,0,0,4.08835,-0.135,-0.0748004,2.48445,2.94176,0.165198, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-3/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-3/tag_size1.220000pose.txt new file mode 100644 index 0000000..9917b27 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-3/tag_size1.220000pose.txt @@ -0,0 +1,74 @@ +iter, id, rot_num, x, y, z, r, p, y +0,0,0,6.1625,-0.00028278,-0.142459,2.5071,2.94889,0.195894, +1,0,0,6.16154,-0.00567222,-0.142105,2.49938,2.94994,0.197963, +4,0,0,6.16214,-0.00514394,-0.142544,2.50192,2.94946,0.197288, +5,0,0,6.16164,-0.0039039,-0.142559,2.51064,2.94702,0.195597, +8,0,0,6.1606,-0.00593356,-0.144991,2.53723,2.94117,0.192466, +9,0,0,6.16238,0.000533201,-0.142523,2.50697,2.94627,0.196288, +10,0,0,6.16153,-0.00427688,-0.143031,2.49834,2.94836,0.198814, +11,0,0,6.16201,-0.00487083,-0.143451,2.50051,2.94923,0.197898, +12,0,0,6.16167,0.00169355,-0.143929,2.48026,2.95228,0.20041, +14,0,0,6.16151,-0.00470928,-0.142987,2.53353,2.9417,0.1913, +15,0,0,6.16164,-0.00214093,-0.144065,2.50422,2.94764,0.196679, +16,0,0,6.16179,-0.00137484,-0.14268,2.50248,2.94838,0.196642, +17,0,0,6.1617,-0.00479749,-0.142607,2.51471,2.9469,0.196133, +20,0,0,6.16192,-0.00665059,-0.142992,2.49817,2.94894,0.200317, +21,0,0,6.16187,-0.00398347,-0.142331,2.51186,2.94676,0.195713, +23,0,0,6.16092,0.000644488,-0.144762,2.47905,2.95056,0.203893, +26,0,0,6.16098,0.000234903,-0.143626,2.48173,2.95142,0.203322, +27,0,0,6.16144,-0.00500301,-0.143279,2.50116,2.94896,0.198203, +28,0,0,6.1615,-0.00496425,-0.14387,2.50158,2.94725,0.198767, +29,0,0,6.16132,0.00242158,-0.144078,2.47598,2.95225,0.203976, +31,0,0,6.16161,-0.00602954,-0.143844,2.50315,2.94763,0.200029, +32,0,0,6.16205,-0.000338067,-0.143669,2.47889,2.95118,0.200583, +36,0,0,6.16189,-0.000926078,-0.141223,2.50593,2.94662,0.197441, +37,0,0,6.16093,-0.0049322,-0.143817,2.4993,2.94775,0.199822, +41,0,0,6.15962,-0.00575367,-0.144941,2.52427,2.94228,0.192355, +42,0,0,6.16083,-8.83674e-05,-0.144753,2.50793,2.94555,0.197662, +43,0,0,6.16156,-0.00543942,-0.142252,2.50055,2.94738,0.199687, +45,0,0,6.16199,-0.00270054,-0.141479,2.50067,2.9476,0.198148, +46,0,0,6.16122,-0.00263188,-0.143205,2.49192,2.9483,0.200974, +48,0,0,6.15947,4.27922e-05,-0.143289,2.48077,2.95039,0.203383, +49,0,0,6.15984,-0.00951649,-0.150152,2.51342,2.94517,0.194809, +50,0,0,6.16127,-0.00167206,-0.143619,2.50757,2.94566,0.197175, +51,0,0,6.16206,-0.00198496,-0.141628,2.49655,2.94988,0.200135, +52,0,0,6.16127,-0.00522259,-0.144365,2.50543,2.94691,0.198597, +53,0,0,6.16105,-0.00242989,-0.142756,2.50966,2.94578,0.198633, +55,0,0,6.16122,-0.00621218,-0.14364,2.50888,2.9447,0.198609, +58,0,0,6.16162,0.00165664,-0.143933,2.47813,2.95168,0.202834, +61,0,0,6.16206,-0.00289772,-0.142712,2.50951,2.94503,0.195106, +62,0,0,6.16195,-0.00505774,-0.144451,2.49483,2.94807,0.20054, +63,0,0,6.16126,-0.0021208,-0.144463,2.47895,2.95104,0.204303, +66,0,0,6.16077,-0.000507824,-0.144221,2.47945,2.9501,0.203968, +68,0,0,6.16211,-0.00284213,-0.142615,2.49824,2.94709,0.199113, +74,0,0,6.16181,-0.0036409,-0.143315,2.49777,2.94707,0.197685, +75,0,0,6.16098,-0.00403359,-0.142133,2.50123,2.94659,0.200022, +78,0,0,6.16189,-0.0031827,-0.143957,2.49969,2.94697,0.200237, +79,0,0,6.1595,-0.00144528,-0.143185,2.50851,2.94391,0.197479, +80,0,0,6.16213,-0.00449242,-0.143137,2.5376,2.93939,0.191974, +81,0,0,6.16155,-0.00489801,-0.14252,2.49622,2.94756,0.200193, +87,0,0,6.16118,0.00159765,-0.145404,2.47557,2.95151,0.204704, +88,0,0,6.16088,-0.00606635,-0.142952,2.51013,2.94546,0.197946, +89,0,0,6.16103,-0.00463328,-0.143919,2.48589,2.95071,0.202909, +93,0,0,6.16054,-0.00239281,-0.143119,2.50532,2.94593,0.200182, +94,0,0,6.16141,-0.00576859,-0.142753,2.51114,2.94451,0.197056, +96,0,0,6.16133,-0.00276053,-0.143596,2.51588,2.94338,0.196714, +97,0,0,6.16047,0.001189,-0.144825,2.4795,2.94984,0.204771, +98,0,0,6.16153,-0.00538415,-0.144151,2.49946,2.94765,0.199997, +99,0,0,6.16128,-0.0035083,-0.142093,2.50969,2.94446,0.198965, +100,0,0,6.16125,-0.00525815,-0.143896,2.50473,2.94586,0.199424, +101,0,0,6.16096,-0.00178056,-0.144189,2.47998,2.95041,0.204574, +104,0,0,6.1612,0.000481998,-0.143548,2.50989,2.94436,0.198076, +107,0,0,6.16086,-0.00584146,-0.144933,2.50956,2.94557,0.197751, +108,0,0,6.16175,0.00172442,-0.138742,2.49883,2.94701,0.199127, +110,0,0,6.15897,-0.00354852,-0.149434,2.49977,2.94825,0.199401, +111,0,0,6.16088,0.00536297,-0.144419,2.47842,2.95065,0.20462, +113,0,0,6.16193,0.010528,-0.135208,2.50248,2.94352,0.202389, +114,0,0,6.16055,0.0046078,-0.146013,2.49257,2.94777,0.199482, +116,0,0,6.16083,0.0039996,-0.143817,2.4867,2.94933,0.202165, +117,0,0,6.16415,0.0069218,-0.132062,2.47581,2.94787,0.207186, +120,0,0,6.16029,0.0101164,-0.150303,2.49982,2.94299,0.201552, +121,0,0,6.15905,-0.00249097,-0.154465,2.50751,2.94342,0.199538, +122,0,0,6.16515,0.00395661,-0.133463,2.48131,2.95266,0.200932, +123,0,0,6.16236,-0.002455,-0.138663,2.49238,2.94858,0.201073, +126,0,0,6.16078,-0.0128376,-0.14593,2.47678,2.95105,0.20331, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-4/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-4/tag_size1.220000pose.txt new file mode 100644 index 0000000..cfd3028 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-4/tag_size1.220000pose.txt @@ -0,0 +1,91 @@ +iter, id, rot_num, x, y, z, r, p, y +1,0,0,8.14261,-0.0927277,-0.143306,2.44671,2.96255,0.182197, +2,0,0,8.14325,-0.0934074,-0.143122,2.50085,2.95235,0.171116, +3,0,0,8.14192,-0.0923142,-0.146347,2.45034,2.96222,0.181426, +4,0,0,8.14417,-0.0893946,-0.137797,2.4825,2.95597,0.1743, +5,0,0,8.14123,-0.0935881,-0.145027,2.47052,2.95983,0.178919, +6,0,0,8.14435,-0.0897985,-0.141559,2.45411,2.9607,0.181374, +8,0,0,8.14279,-0.0922531,-0.143145,2.48771,2.95685,0.17537, +10,0,0,8.14299,-0.0909011,-0.144928,2.45202,2.96097,0.181454, +11,0,0,8.1424,-0.0912118,-0.143228,2.48038,2.95731,0.176466, +12,0,0,8.14391,-0.0927644,-0.139085,2.47133,2.95853,0.178546, +13,0,0,8.14327,-0.093445,-0.14299,2.47436,2.95744,0.17741, +15,0,0,8.14347,-0.0893641,-0.143215,2.47277,2.95726,0.176696, +16,0,0,8.14216,-0.0931144,-0.143882,2.48973,2.95557,0.174058, +17,0,0,8.14229,-0.0893987,-0.146162,2.45171,2.96231,0.180233, +18,0,0,8.14341,-0.0918517,-0.139363,2.46344,2.96069,0.177825, +19,0,0,8.14303,-0.092915,-0.142393,2.45991,2.96042,0.180588, +22,0,0,8.1422,-0.0944699,-0.144736,2.49077,2.95488,0.174475, +23,0,0,8.14219,-0.0943615,-0.142043,2.48768,2.95477,0.174736, +24,0,0,8.14288,-0.0915003,-0.142215,2.48109,2.95746,0.175469, +26,0,0,8.14286,-0.0924077,-0.145121,2.46666,2.95949,0.179688, +28,0,0,8.14338,-0.0926453,-0.143282,2.47737,2.95695,0.175507, +29,0,0,8.14245,-0.0941457,-0.143982,2.46594,2.96022,0.178984, +30,0,0,8.14177,-0.0939447,-0.146027,2.45391,2.96178,0.181622, +32,0,0,8.14287,-0.0901423,-0.141604,2.47319,2.95791,0.176491, +34,0,0,8.14125,-0.0926111,-0.143797,2.4666,2.96144,0.18066, +35,0,0,8.14314,-0.09458,-0.143396,2.49221,2.95464,0.174282, +37,0,0,8.14304,-0.0881693,-0.142099,2.45044,2.96296,0.18071, +38,0,0,8.14257,-0.0928198,-0.142201,2.45166,2.9613,0.179579, +39,0,0,8.14262,-0.0908795,-0.144501,2.45384,2.96051,0.181184, +41,0,0,8.14417,-0.0898046,-0.138454,2.48398,2.9554,0.177162, +46,0,0,8.14389,-0.0928718,-0.141177,2.48294,2.95669,0.174992, +47,0,0,8.14127,-0.0916706,-0.146995,2.45166,2.96272,0.180915, +48,0,0,8.14353,-0.0930968,-0.142882,2.47244,2.95901,0.176754, +51,0,0,8.14234,-0.091319,-0.143561,2.45481,2.96163,0.180544, +52,0,0,8.13834,-0.0997912,-0.163789,2.48068,2.95581,0.178465, +53,0,0,8.14528,-0.0834573,-0.132816,2.48643,2.9564,0.175164, +55,0,0,8.14673,-0.088222,-0.129933,2.48457,2.95915,0.173459, +57,0,0,8.14354,-0.0907055,-0.138652,2.49014,2.95939,0.173784, +58,0,0,8.1408,-0.0790644,-0.148417,2.453,2.95901,0.180776, +59,0,0,8.14297,-0.0865044,-0.144707,2.4875,2.9544,0.174249, +61,0,0,8.13882,-0.0836124,-0.157583,2.48653,2.955,0.17428, +62,0,0,8.14594,-0.085988,-0.130186,2.48459,2.9531,0.17729, +63,0,0,8.14008,-0.0995994,-0.157252,2.47584,2.95669,0.177408, +65,0,0,8.13733,-0.0949208,-0.168018,2.47002,2.95692,0.180998, +66,0,0,8.14348,-0.100706,-0.145196,2.48284,2.95585,0.176678, +68,0,0,8.13941,-0.0960988,-0.155667,2.47621,2.9581,0.177488, +69,0,0,8.14572,-0.0972995,-0.12969,2.46715,2.95659,0.178794, +70,0,0,8.13941,-0.10138,-0.15916,2.48061,2.95478,0.177848, +72,0,0,8.13813,-0.100277,-0.160706,2.45245,2.96163,0.181011, +73,0,0,8.14492,-0.0977674,-0.13119,2.47781,2.95536,0.177193, +74,0,0,8.14165,-0.102918,-0.146194,2.50314,2.95217,0.172099, +75,0,0,8.14724,-0.0956439,-0.127047,2.47133,2.96201,0.177087, +76,0,0,8.14347,-0.0991645,-0.141447,2.47029,2.95784,0.176068, +78,0,0,8.14499,-0.0905112,-0.135526,2.50507,2.95288,0.172023, +79,0,0,8.14305,-0.0896306,-0.145013,2.46438,2.96044,0.177044, +80,0,0,8.14214,-0.0890589,-0.142976,2.47351,2.95748,0.177482, +81,0,0,8.14298,-0.0919431,-0.144907,2.49005,2.9554,0.173811, +84,0,0,8.14139,-0.0899306,-0.145796,2.5003,2.95328,0.172531, +85,0,0,8.14263,-0.0910821,-0.143305,2.47562,2.95797,0.177454, +86,0,0,8.14187,-0.0909055,-0.14416,2.50954,2.95219,0.170357, +88,0,0,8.14294,-0.0937674,-0.143206,2.45283,2.96266,0.181048, +91,0,0,8.14214,-0.0942288,-0.145926,2.45164,2.96209,0.18113, +93,0,0,8.14235,-0.0952476,-0.144095,2.49021,2.95584,0.172893, +94,0,0,8.1438,-0.0913974,-0.141861,2.4712,2.95807,0.177356, +95,0,0,8.14247,-0.0967592,-0.14579,2.48999,2.95629,0.173438, +96,0,0,8.14492,-0.0903831,-0.137749,2.45912,2.95953,0.180405, +98,0,0,8.14193,-0.0961748,-0.145702,2.48215,2.95887,0.177374, +100,0,0,8.14232,-0.0964826,-0.143766,2.48421,2.95695,0.175685, +102,0,0,8.14331,-0.0910354,-0.137467,2.46376,2.95838,0.178641, +103,0,0,8.14167,-0.0977858,-0.146249,2.4622,2.96168,0.179734, +105,0,0,8.14257,-0.0909201,-0.143481,2.48734,2.95707,0.174966, +107,0,0,8.14358,-0.0939791,-0.142322,2.48853,2.95581,0.174789, +109,0,0,8.14183,-0.0923909,-0.144069,2.50704,2.95265,0.17254, +110,0,0,8.14351,-0.094669,-0.140823,2.48197,2.95751,0.174203, +111,0,0,8.14295,-0.0915638,-0.141842,2.47681,2.95727,0.175135, +112,0,0,8.14317,-0.0921837,-0.142504,2.45412,2.96143,0.182341, +113,0,0,8.14176,-0.0913974,-0.14571,2.49472,2.95381,0.17362, +114,0,0,8.1443,-0.0912375,-0.138038,2.46838,2.95815,0.178712, +115,0,0,8.14238,-0.0918005,-0.145153,2.45345,2.96058,0.180693, +116,0,0,8.1427,-0.0928264,-0.14172,2.49023,2.95621,0.174662, +117,0,0,8.1427,-0.0949222,-0.143482,2.47239,2.95925,0.175863, +118,0,0,8.14258,-0.0924072,-0.142368,2.47038,2.95791,0.178603, +119,0,0,8.14409,-0.0940999,-0.14191,2.48306,2.9578,0.174526, +120,0,0,8.14246,-0.0930418,-0.143818,2.47494,2.95834,0.175952, +121,0,0,8.14356,-0.0886632,-0.140699,2.49211,2.95412,0.172848, +123,0,0,8.14359,-0.0939157,-0.141789,2.4904,2.95711,0.172659, +125,0,0,8.14338,-0.0908353,-0.143044,2.47247,2.95832,0.176909, +126,0,0,8.14301,-0.09121,-0.145041,2.45133,2.96223,0.180351, +129,0,0,8.14217,-0.0889572,-0.142857,2.51096,2.95217,0.170815, +130,0,0,8.14342,-0.0943972,-0.143146,2.48019,2.95776,0.175709, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-5/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-5/tag_size1.220000pose.txt new file mode 100644 index 0000000..934535d --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-5/tag_size1.220000pose.txt @@ -0,0 +1,66 @@ +iter, id, rot_num, x, y, z, r, p, y +3,0,0,9.95313,0.167361,-0.235544,2.47539,2.95817,0.209369, +4,0,0,9.96383,0.189551,-0.18539,2.50162,2.95545,0.205584, +5,0,0,9.95371,0.183895,-0.226327,2.49141,2.95929,0.203479, +9,0,0,9.95985,0.177674,-0.20679,2.49811,2.95718,0.202505, +17,0,0,9.96049,0.183471,-0.20624,2.48851,2.95794,0.204771, +18,0,0,9.95852,0.194571,-0.211197,2.49568,2.95906,0.203028, +19,0,0,9.96276,0.178105,-0.202265,2.48285,2.96236,0.204666, +21,0,0,9.96189,0.179265,-0.201973,2.47546,2.96219,0.204428, +22,0,0,9.96001,0.182882,-0.206296,2.48999,2.95852,0.203102, +25,0,0,9.95848,0.177006,-0.208398,2.49812,2.95692,0.202468, +28,0,0,9.96022,0.182265,-0.20569,2.49079,2.95855,0.203617, +34,0,0,9.95848,0.183226,-0.208844,2.49616,2.95781,0.203887, +35,0,0,9.9619,0.177396,-0.204429,2.49325,2.95959,0.202775, +36,0,0,9.95549,0.172787,-0.223217,2.48827,2.95793,0.202696, +37,0,0,9.96126,0.178821,-0.202738,2.47848,2.96126,0.208275, +38,0,0,9.95819,0.186887,-0.208509,2.48816,2.95736,0.205505, +42,0,0,9.95811,0.184998,-0.209781,2.47736,2.96081,0.207977, +43,0,0,9.95871,0.164128,-0.215176,2.47867,2.96006,0.20525, +44,0,0,9.95794,0.183571,-0.213072,2.48356,2.95739,0.208148, +46,0,0,9.95967,0.181906,-0.208771,2.48047,2.96078,0.206226, +47,0,0,9.95738,0.184741,-0.210321,2.48725,2.95724,0.204317, +48,0,0,9.95978,0.17748,-0.211376,2.49271,2.95849,0.204246, +51,0,0,9.95978,0.185055,-0.210652,2.48616,2.95609,0.205958, +53,0,0,9.95904,0.186121,-0.212828,2.48754,2.95805,0.203729, +54,0,0,9.9579,0.188371,-0.208784,2.48444,2.95866,0.206652, +56,0,0,9.95982,0.177605,-0.206501,2.48752,2.95877,0.205799, +59,0,0,9.95606,0.171169,-0.220118,2.47722,2.96092,0.20668, +61,0,0,9.95867,0.185001,-0.2096,2.49288,2.95834,0.204908, +62,0,0,9.9618,0.180889,-0.201226,2.4971,2.9573,0.200682, +64,0,0,9.9584,0.185792,-0.212765,2.47542,2.96063,0.208072, +66,0,0,9.95857,0.184064,-0.216056,2.48912,2.95768,0.205451, +67,0,0,9.95839,0.184993,-0.20899,2.51046,2.95381,0.200198, +68,0,0,9.96055,0.182995,-0.20336,2.49653,2.95976,0.202315, +70,0,0,9.96023,0.183153,-0.20751,2.48285,2.95817,0.204072, +71,0,0,9.96154,0.183756,-0.20465,2.48984,2.95977,0.202224, +77,0,0,9.95967,0.181761,-0.206481,2.47929,2.96212,0.206568, +78,0,0,9.95816,0.181416,-0.210488,2.48743,2.95713,0.205748, +79,0,0,9.95949,0.180221,-0.211428,2.48377,2.95886,0.205122, +80,0,0,9.95916,0.176909,-0.213407,2.47324,2.95923,0.208571, +81,0,0,9.96009,0.183442,-0.209302,2.47677,2.96271,0.205898, +82,0,0,9.95814,0.185456,-0.216168,2.48536,2.95628,0.207443, +85,0,0,9.96296,0.174989,-0.198887,2.4887,2.96208,0.203063, +86,0,0,9.96031,0.183255,-0.207938,2.47694,2.96003,0.207404, +87,0,0,9.95828,0.185098,-0.209999,2.49414,2.95821,0.203939, +90,0,0,9.96012,0.181624,-0.207199,2.48331,2.95922,0.203982, +91,0,0,9.95877,0.184415,-0.208008,2.47634,2.96136,0.209305, +94,0,0,9.95742,0.185391,-0.211581,2.48861,2.95785,0.206339, +95,0,0,9.95883,0.179218,-0.214216,2.51054,2.95435,0.201997, +97,0,0,9.95845,0.175274,-0.212258,2.48762,2.96008,0.202955, +104,0,0,9.9594,0.181661,-0.210027,2.48332,2.95926,0.20597, +106,0,0,9.95847,0.182221,-0.209058,2.48423,2.95823,0.208527, +107,0,0,9.96081,0.175618,-0.209065,2.48116,2.96119,0.204664, +108,0,0,9.9605,0.185227,-0.203629,2.491,2.95887,0.204279, +110,0,0,9.95961,0.184056,-0.206649,2.49454,2.96036,0.202123, +111,0,0,9.96156,0.174405,-0.202811,2.47271,2.96242,0.206389, +112,0,0,9.95742,0.182691,-0.212503,2.49187,2.95627,0.205142, +113,0,0,9.96192,0.180095,-0.2006,2.47013,2.96266,0.206206, +116,0,0,9.96192,0.17661,-0.198978,2.46495,2.96473,0.20816, +117,0,0,9.96187,0.177341,-0.201289,2.49511,2.95882,0.201503, +119,0,0,9.96059,0.182478,-0.20267,2.50509,2.95506,0.201951, +120,0,0,9.95988,0.185641,-0.212635,2.48558,2.95974,0.205432, +122,0,0,9.95881,0.183553,-0.211168,2.48971,2.95699,0.20501, +123,0,0,9.96194,0.179551,-0.201648,2.48128,2.9609,0.203596, +125,0,0,9.95966,0.185949,-0.209098,2.47792,2.95928,0.207388, +127,0,0,9.96163,0.175455,-0.203828,2.49431,2.95806,0.202041, diff --git a/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-6/tag_size1.220000pose.txt b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-6/tag_size1.220000pose.txt new file mode 100644 index 0000000..9a111d5 --- /dev/null +++ b/matlab/new_preprocess/predictions/mocap_prediction/straight_front1-6/tag_size1.220000pose.txt @@ -0,0 +1,64 @@ +iter, id, rot_num, x, y, z, r, p, y +0,0,0,12.1342,0.0429193,-0.32839,2.52738,2.93557,0.182746, +6,0,0,12.1375,0.0441842,-0.324712,2.44418,2.95095,0.199944, +9,0,0,12.1354,0.05457,-0.323482,2.52807,2.93758,0.18122, +10,0,0,12.1374,0.0486864,-0.321623,2.56435,2.93166,0.176315, +11,0,0,12.1342,0.0521648,-0.325552,2.51261,2.93943,0.186738, +13,0,0,12.1324,0.0507367,-0.337302,2.49548,2.94086,0.190458, +14,0,0,12.1343,0.0501588,-0.324841,2.48931,2.94195,0.190176, +15,0,0,12.1349,0.0479336,-0.324228,2.5002,2.94213,0.186902, +19,0,0,12.1361,0.0441244,-0.327737,2.55517,2.9301,0.17707, +22,0,0,12.1325,0.0483902,-0.334589,2.54784,2.93188,0.179484, +24,0,0,12.1328,0.0522052,-0.328583,2.51326,2.93708,0.187169, +25,0,0,12.135,0.0479396,-0.325066,2.52696,2.9362,0.182699, +26,0,0,12.1359,0.0480471,-0.323724,2.45061,2.94961,0.198021, +28,0,0,12.1347,0.0513409,-0.32652,2.52593,2.93456,0.181626, +32,0,0,12.1348,0.0487743,-0.324788,2.52906,2.9335,0.179401, +33,0,0,12.1352,0.0522715,-0.327473,2.48512,2.9448,0.192159, +38,0,0,12.134,0.0523731,-0.326182,2.50999,2.93928,0.188296, +39,0,0,12.1351,0.0453851,-0.32383,2.50841,2.93913,0.185233, +42,0,0,12.1357,0.0510683,-0.318156,2.5254,2.93817,0.185079, +43,0,0,12.1369,0.0411874,-0.325373,2.52174,2.93717,0.185607, +44,0,0,12.1357,0.0500759,-0.323167,2.53033,2.93727,0.182193, +45,0,0,12.1339,0.051354,-0.324969,2.50036,2.94048,0.187761, +49,0,0,12.1352,0.0454079,-0.325242,2.50864,2.93985,0.187294, +51,0,0,12.1352,0.0446005,-0.323992,2.52907,2.93656,0.181125, +52,0,0,12.1373,0.0524061,-0.323962,2.53926,2.93563,0.180282, +54,0,0,12.1333,0.0481188,-0.333336,2.45003,2.94983,0.199439, +56,0,0,12.1378,0.0444749,-0.322038,2.50403,2.93911,0.189469, +59,0,0,12.1348,0.0520202,-0.326254,2.49506,2.9421,0.191808, +60,0,0,12.1366,0.0492128,-0.323778,2.55677,2.93106,0.177301, +61,0,0,12.1364,0.0521127,-0.3222,2.51028,2.93788,0.184425, +62,0,0,12.1313,0.0536603,-0.332218,2.48752,2.94389,0.19291, +64,0,0,12.1356,0.0482435,-0.321836,2.51924,2.93863,0.18469, +69,0,0,12.1356,0.0524531,-0.322727,2.52764,2.93609,0.182344, +70,0,0,12.1373,0.0451971,-0.317384,2.51376,2.93926,0.184428, +72,0,0,12.1353,0.0490977,-0.3279,2.48166,2.9445,0.192676, +74,0,0,12.1357,0.0496434,-0.324331,2.48515,2.94392,0.191461, +76,0,0,12.1374,0.0482295,-0.32013,2.45882,2.94953,0.196443, +78,0,0,12.1353,0.049482,-0.322551,2.48369,2.94443,0.193383, +80,0,0,12.1343,0.0519175,-0.322004,2.50005,2.94202,0.186077, +83,0,0,12.1378,0.0485671,-0.319641,2.46732,2.94893,0.194404, +87,0,0,12.1329,0.0509356,-0.331021,2.50003,2.93988,0.187966, +88,0,0,12.1372,0.0487975,-0.318315,2.49942,2.94224,0.187394, +89,0,0,12.1348,0.0444004,-0.327884,2.45806,2.94961,0.195326, +90,0,0,12.1364,0.0449397,-0.325506,2.51999,2.937,0.184509, +92,0,0,12.1358,0.0455999,-0.329552,2.45767,2.94891,0.198639, +95,0,0,12.1365,0.0516637,-0.322166,2.52754,2.93449,0.180662, +100,0,0,12.1322,0.0519683,-0.331583,2.49395,2.94029,0.192243, +101,0,0,12.1363,0.0523628,-0.325106,2.55099,2.93043,0.178326, +103,0,0,12.1373,0.0419874,-0.322737,2.49726,2.94119,0.190114, +105,0,0,12.1353,0.0461269,-0.322939,2.52711,2.9368,0.181454, +106,0,0,12.1361,0.0528825,-0.319628,2.49798,2.94146,0.188229, +107,0,0,12.1348,0.0515008,-0.326182,2.52832,2.93683,0.183286, +109,0,0,12.1368,0.0378611,-0.326025,2.486,2.9437,0.19132, +112,0,0,12.1379,0.042374,-0.322365,2.56437,2.92968,0.174597, +114,0,0,12.1366,0.0445021,-0.322915,2.53157,2.93663,0.183388, +116,0,0,12.1363,0.0488531,-0.324165,2.55511,2.93218,0.177589, +121,0,0,12.1369,0.048039,-0.324056,2.51107,2.93981,0.185663, +123,0,0,12.1328,0.0543901,-0.332433,2.48396,2.94447,0.192565, +125,0,0,12.1335,0.0500179,-0.334597,2.54925,2.93194,0.178987, +126,0,0,12.1371,0.0476564,-0.317382,2.5238,2.93843,0.185082, +127,0,0,12.1359,0.0401377,-0.324014,2.49355,2.94167,0.191145, +129,0,0,12.1334,0.05222,-0.331181,2.51206,2.93885,0.186737, +130,0,0,12.1343,0.044764,-0.327645,2.42511,2.95398,0.205326, diff --git a/matlab/new_preprocess/read_txt.m b/matlab/new_preprocess/read_txt.m new file mode 100644 index 0000000..b9d2f9c --- /dev/null +++ b/matlab/new_preprocess/read_txt.m @@ -0,0 +1,2 @@ +clear; +x = dlmread('ccw1-1.txt',',',1,0); \ No newline at end of file diff --git a/matlab/new_preprocess/staight-front0.mat b/matlab/new_preprocess/staight-front0.mat new file mode 100644 index 0000000..1bcbc20 Binary files /dev/null and b/matlab/new_preprocess/staight-front0.mat differ diff --git a/matlab/new_preprocess/staightfront1.m b/matlab/new_preprocess/staightfront1.m new file mode 100644 index 0000000..83208a6 --- /dev/null +++ b/matlab/new_preprocess/staightfront1.m @@ -0,0 +1,109 @@ +clear +file = load('straight-front1.mat'); +total_frames = file.straight_front1.Frames; +for k = 1:file.straight_front1.RigidBodies.Bodies + if strcmp(file.straight_front1.RigidBodies.Name(k),'lidar') + lidar_pos_raw = file.straight_front1.RigidBodies.Positions(k,:,:); + lidar_rot_raw = file.straight_front1.RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = file.straight_front1.RigidBodies.Positions(k,:,:); + tag_rot_raw = file.straight_front1.RigidBodies.Rotations(k,:,:); + end +end + +n = 1; +invalid_num = 0; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || any(isnan(tag_rot_raw(:,:,m))); + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end +valid_frames = n - 1; +x = 1:valid_frames; +y = squeeze(lidar_pos(1,2,:)); +figure(1); +scatter(x,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1,1,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1,3,:)); +figure(3); +scatter(p,q,'filled'); + +mocap_to_lidar_change_of_basis = [0 1 0 0; 1 0 0 0; 0 0 -1 0; 0 0 0 1]; +new_basis = mocap_to_lidar_change_of_basis; +%straight_front_1 +distance(1,:) = [44,2188]; +distance(2,:) = [2900,3252]; +distance(3,:) = [4053,4681]; +distance(4,:) = [5026,5498]; +distance(5,:) = [6935,8542]; +distance(6,:) = [8977,9519]; +for i = 1:6 + lidar_pos_mean = mean(lidar_pos(1,:,distance(i,1):distance(i,2)),3); + lidar_rot_mean = mean(lidar_rot(1,:,distance(i,1):distance(i,2)),3); + tag_pos_mean = mean(tag_pos(1,:,distance(i,1):distance(i,2)),3); + tag_rot_mean = mean(tag_rot(1,:,distance(i,1):distance(i,2)),3); + lidar_rotm = reshape(lidar_rot_mean,3,3); + tag_rotm = reshape(tag_rot_mean,3,3); + world_H_tag = createSE3(tag_rotm, tag_pos_mean'); + world_H_lidar = createSE3(lidar_rotm, lidar_pos_mean'); + lidar_H_tag = world_H_lidar \ world_H_tag; + lidar_H_tag_t = new_basis * lidar_H_tag * inv(new_basis); + angles = rotm2eul(lidar_H_tag_t(1:3,1:3), 'XYZ'); +% angles = fliplr(angles)'; +% angles = flipud(new_basis*angles)'; + tag_rotm_lidar(i,:) = angles*180/pi; +% tag_pos_lidar(i,:) = new_basis*lidar_H_tag(1:3,4)/1000; + tag_pos_lidar(i,:) = lidar_H_tag_t(1:3,4)/1000; +end +tag_rotm_lidar +tag_pos_lidar +for i = 1:5 + file_name = strcat('lidar_front',int2str(i+1),'.txt'); + x = dlmread(file_name,',',1,0); + lidar_pose_prediction_L(i,:) = mean(x(:,4:6),1); + lidar_rot_prediction_L(i,:) = mean(x(:,7:9),1)*180/pi; +end +for i = 1:5 + file_name = strcat('april_front',int2str(i+1),'.txt'); + x = dlmread(file_name,',',1,0); + april_pose_prediction_L(i,:) = mean(x(:,3:5),1); + april_rot_prediction_L(i,:) = mean(x(:,6:8),1)*180/pi; +end +lidar_rot_prediction_L +lidar_pose_prediction_L +figure(1); +delta_x_meter = lidar_pose_prediction_L(:,1) - tag_pos_lidar(2:6,1); +plot(tag_pos_lidar(2:6,1),delta_x_meter); +figure(2); +delta_y_meter = lidar_pose_prediction_L(:,2) - tag_pos_lidar(2:6,2); +plot(tag_pos_lidar(2:6,1),delta_y_meter); +figure(3); +delta_z_meter = lidar_pose_prediction_L(:,3) - tag_pos_lidar(2:6,3); +plot(tag_pos_lidar(2:6,1),delta_z_meter); +figure(4); +delta_r_degree = lidar_rot_prediction_L(:,1) - tag_rotm_lidar(2:6,1); +plot(tag_pos_lidar(2:6,1),delta_r_degree); +figure(5); +delta_p_degree = lidar_rot_prediction_L(:,2) - tag_rotm_lidar(2:6,2); +plot(tag_pos_lidar(2:6,1),delta_p_degree); +figure(6); +delta_yaw_degree = lidar_rot_prediction_L(:,3) - tag_rotm_lidar(2:6,3); +plot(tag_pos_lidar(2:6,1),delta_yaw_degree); +Distance_meter = tag_pos_lidar(2:6,1); +T = table(Distance_meter,delta_x_meter,delta_y_meter,delta_z_meter,delta_r_degree,delta_p_degree,delta_yaw_degree) \ No newline at end of file diff --git a/matlab/new_preprocess/straight_front1.mat b/matlab/new_preprocess/straight_front1.mat new file mode 100644 index 0000000..e9e7507 Binary files /dev/null and b/matlab/new_preprocess/straight_front1.mat differ diff --git a/matlab/restuls.m b/matlab/restuls.m new file mode 100644 index 0000000..766fe4d --- /dev/null +++ b/matlab/restuls.m @@ -0,0 +1,75 @@ +clc, clear +data_num = 3; +path = "./paper_data_pre/lidartag_estimates/"; + +switch data_num + case 1 + dataset = "straight-ccw1-3"; + case 2 + dataset = "lab3"; + case 3 + dataset = "ccw1-3"; +end +path_folder = path + dataset + "/"; +delimiterIn = ','; +headerlinesIn = 1; + + +%% Computation time +name = "timing_computation_only.txt"; +filename = path_folder +name; +data = importdata(filename, delimiterIn, headerlinesIn); + +for k = 1:size(data.data, 2) +% timing.(genvarname(data.colheaders{1, k})) = data.data(:, k); + computation_mean.(genvarname(string(data.colheaders{1, k}) + "_mean")) = mean(data.data(:, k)); + computation_hz.(genvarname(string(data.colheaders{1, k}) + "_Hz")) = 1000/mean(data.data(:, k)); +end +% struct2table(computation_mean) + + +%% Decoding +name = "decoding_analysis.txt"; +filename = path_folder + name; +data = importdata(filename, delimiterIn, headerlinesIn); + +for k = 1:size(data.data, 2) + decoding_hz.(genvarname(string(data.colheaders{1, k}) + "_Hz")) = 1e3/mean(data.data(:, k)); +end + +%% Timings +% name = "computation_time.txt"; +name = "timing_all.txt"; +filename = path_folder +name; +data = importdata(filename, delimiterIn, headerlinesIn); + +for k = 1:size(data.data, 2) +% timing.(genvarname(data.colheaders{1, k})) = data.data(:, k); + timing_mean.(genvarname(string(data.colheaders{1, k}) + "_mean")) = mean(data.data(:, k)); + timing_hz.(genvarname(string(data.colheaders{1, k}) + "_Hz")) = 1000/mean(data.data(:, k)); +end +% struct2table(timing_mean) + + + +%% Clusters +% name = "computation_time.txt"; +name = "stats.txt"; +filename = path_folder + name; +data = importdata(filename, delimiterIn, headerlinesIn); + +for k = 1:size(data.data, 2) +% records.(genvarname(data.colheaders{1, k})) = data.data(:, k); + clusters.(genvarname(string(data.colheaders{1, k}) + "_mean")) = mean(data.data(:, k)); +end + + +fprintf("Each of below sums over %i scans from %s dataset: \n", size(data.data, 1), dataset) +struct2table(computation_hz) +struct2table(decoding_hz) +struct2table(timing_hz) +struct2table(clusters) + + + +disp("All done") \ No newline at end of file diff --git a/matlab/single_dataset.m b/matlab/single_dataset.m new file mode 100644 index 0000000..3023bd8 --- /dev/null +++ b/matlab/single_dataset.m @@ -0,0 +1,78 @@ +clc, clear +data_num = 4; +path = "./paper_data_pre/lidartag_estimates/"; + + + +switch data_num + case 1 + dataset = "straight-ccw1-3"; + case 2 + dataset = "lab3"; + case 3 + dataset = "ccw1-3"; + case 4 + dataset = "new-lab2"; + case 5 + path = "./paper_data/public_datasets/"; + dataset = "cartographer/horizontal_lidar"; + case 6 + path = "./paper_data/public_datasets/"; + dataset = "cartographer/vertical_lidar"; + case 7 + path = "./paper_data/public_datasets/"; + dataset = "H3D"; + case 8 + dataset = "lab-small-middle"; + case 9 + dataset = "Oct01-2020/ccw1-5"; +% dataset = "Oct07-2020/ccw1-8"; +end +path_folder = path + dataset + "/"; +delimiterIn = ','; +headerlinesIn = 1; + + +lidartag = analyzeLiDARTagPackage([], path_folder); + +disp("===============================================================") +disp("============= Summary Results of General Analysis =============") +disp("===============================================================") +% summary_t = summarizeGeneralAnalysis(lidartag); + +% disp("-----------------------------------------------------------") +% fprintf("Average over all dadtasets with %i scans \n", ... +% summary_t.total_scans) +% disp("-----------------------------------------------------------") + +% if ~isempty(lidartag.timing_hz) +% t1 = struct2table(lidartag.timing_hz) +% end +% + +% if ~isempty(lidartag.computation_mean) +% +% t4 = struct2table(lidartag.computation_mean) +% end + +if ~isempty(lidartag.computation_hz) + disp("---------- Computation time in hz ----------") + struct2table(lidartag.computation_hz) +end + + +if ~isempty(lidartag.timing_mean) + disp("---------- Timine Each step in ms ----------") + struct2table(lidartag.timing_mean) +end + + +if ~isempty(lidartag.clusters) + disp("---------- Remaining Clusters ----------") + struct2table(lidartag.clusters) +end + +if ~isempty(lidartag.decoding_mean) + disp("---------- Speed of Decoding ----------") + struct2table(lidartag.decoding_mean) +end \ No newline at end of file diff --git a/matlab/summarizeGeneralAnalysis.m b/matlab/summarizeGeneralAnalysis.m new file mode 100644 index 0000000..17124c8 --- /dev/null +++ b/matlab/summarizeGeneralAnalysis.m @@ -0,0 +1,132 @@ +function summary_t = summarizeGeneralAnalysis(lidartag, suffix) + counter_general = 0; + counter_decoding = 0; + summary_t = struct('total_scans', 0); + for i = 1:size(lidartag, 2) + dataset_num = i; + if isempty(lidartag(dataset_num).num_data) + warning("No results for %s", lidartag(dataset_num).name) + else + summary_t.total_scans = ... + summary_t.total_scans + lidartag(dataset_num).num_data; + if ~exist('sum_computation_mat', 'var') + sum_computation_mat = zeros(numel(fieldnames(... + lidartag(dataset_num).("computation_" + suffix))), 1); + end + + if ~exist('sum_timing_mat', 'var') + sum_timing_mat = zeros(numel(fieldnames(... + lidartag(dataset_num).("timing_" + suffix))), 1); + end + + if ~exist('sum_clusters_mat', 'var') + sum_clusters_mat = zeros(numel(fieldnames(... + lidartag(dataset_num).clusters)), 1); + end + + + sum_computation_mat = ... + sum_computation_mat + ... + cell2mat(struct2cell(... + lidartag(dataset_num).("computation_" + suffix))); + if ~isfield('computation_hz', summary_t) + summary_t.("computation_" + suffix) = ... + lidartag(dataset_num).("computation_" + suffix); + end + + sum_timing_mat = ... + sum_timing_mat + ... + cell2mat(struct2cell(... + lidartag(dataset_num).("timing_" + suffix))); + if ~isfield('timing_hz', summary_t) + summary_t.("timing_" + suffix) = ... + lidartag(dataset_num).("timing_" + suffix); + end + + sum_clusters_mat = ... + sum_clusters_mat + ... + cell2mat(struct2cell(... + lidartag(dataset_num).clusters)); + if ~isfield('clusters', summary_t) + summary_t.clusters = ... + lidartag(dataset_num).clusters; + end + + counter_general = counter_general + 1; + + if isempty(lidartag(dataset_num).("decoding_" + suffix)) +% warning("No decoding_hz for %s dataset", ... +% lidartag(dataset_num).name) + else + if ~exist('sum_decoding_mat', 'var') + sum_decoding_mat = zeros(numel(fieldnames(... + lidartag(dataset_num).("decoding_" + suffix))), 1); + end + sum_decoding_mat = ... + sum_decoding_mat + ... + cell2mat(struct2cell(... + lidartag(dataset_num).("decoding_" + suffix))); + + if ~isfield('decoding_hz', summary_t) + summary_t.("decoding_" + suffix) = ... + lidartag(dataset_num).("decoding_" + suffix); + end + counter_decoding = counter_decoding + 1; + end + end + end + ave_computation = sum_computation_mat ./ counter_general; + ave_timing = sum_timing_mat ./ counter_general; + ave_clusters = sum_clusters_mat ./ counter_general; + + if exist('sum_decoding_mat', 'var') + ave_decoding = sum_decoding_mat ./ counter_decoding; + end + + + + computation_field_names = fieldnames(summary_t.("computation_" + suffix)); + assert(length(ave_computation)==length(computation_field_names)); + for i = 1:length(ave_computation) + summary_t.("computation_" + suffix).(string(computation_field_names(i))) = ... + ave_computation(i); + end + + timing_field_names = fieldnames(summary_t.("timing_" + suffix)); + assert(length(ave_timing)==length(timing_field_names)); + for i = 1:length(ave_timing) + summary_t.("timing_" + suffix).(string(timing_field_names(i))) = ... + ave_timing(i); + end + + cluster_field_names = fieldnames(summary_t.clusters); + assert(length(ave_clusters)==length(cluster_field_names)); + for i = 1:length(ave_clusters) + summary_t.clusters.(string(cluster_field_names(i))) = ... + ave_clusters(i); + end + + if isfield('decoding_hz', summary_t) + decoding_field_names = fieldnames(summary_t.("decoding_" + suffix)); + assert(length(ave_decoding)==length(decoding_field_names)); + for i = 1:length(ave_decoding) + summary_t.("decoding_" + suffix).(string(decoding_field_names(i))) = ... + ave_decoding(i); + end + end +end + + + + + + + + + + + + + + + diff --git a/matlab/tag_size1.220000pose.txt b/matlab/tag_size1.220000pose.txt new file mode 100644 index 0000000..f3f7423 --- /dev/null +++ b/matlab/tag_size1.220000pose.txt @@ -0,0 +1,78 @@ +iter, id, rot_num, x, y, z, r11, r12, r13, r21, r22, r23, r31, r32, r33 + +0,0,3,6.41502, -0.418442, -0.150237, -0.888538, 0.0218962, 0.458281, -0.392471, -0.553615, -0.734491, 0.237629, -0.832485, 0.500502 +1,0,3,6.41418, -0.416368, -0.148241, -0.889082, 0.0135193, 0.457548, -0.391685, -0.539752, -0.745152, 0.236889, -0.841716, 0.485179 +3,0,3,6.41582, -0.419347, -0.146684, -0.889084, 0.0161444, 0.45746, -0.391378, -0.545095, -0.741414, 0.23739, -0.838219, 0.490954 +4,0,3,6.41314, -0.408395, -0.141856, -0.889458, 0.025585, 0.456301, -0.391836, -0.556574, -0.732591, 0.235222, -0.830404, 0.505074 +13,0,3,6.41554, -0.418637, -0.147718, -0.889158, 0.0256056, 0.456883, -0.391846, -0.558264, -0.731299, 0.236336, -0.829268, 0.506419 +14,0,3,6.41327, -0.416281, -0.14865, -0.888998, 0.010607, 0.457788, -0.392443, -0.532777, -0.749758, 0.235947, -0.846189, 0.477801 +15,0,3,6.4165, -0.420135, -0.14885, -0.888975, 0.0220714, 0.457424, -0.392125, -0.552646, -0.735405, 0.236562, -0.833124, 0.499944 +16,0,3,6.41531, -0.417752, -0.147198, -0.888697, 0.0259538, 0.45776, -0.39282, -0.557991, -0.730985, 0.236454, -0.829441, 0.50608 +17,0,3,6.41528, -0.4186, -0.148713, -0.888497, 0.0197212, 0.458459, -0.391811, -0.552664, -0.735559, 0.238868, -0.833171, 0.498768 +18,0,3,6.41571, -0.426648, -0.158966, -0.88828, 0.0177472, 0.458959, -0.392699, -0.547602, -0.738864, 0.238214, -0.836551, 0.493393 +21,0,3,6.41615, -0.418977, -0.145929, -0.888825, 0.0249345, 0.457569, -0.392419, -0.557054, -0.731915, 0.236641, -0.830102, 0.504908 +23,0,3,6.41361, -0.411471, -0.140795, -0.888958, 0.0222628, 0.457447, -0.392003, -0.553476, -0.734845, 0.236826, -0.832567, 0.500744 +24,0,3,6.41487, -0.416513, -0.14815, -0.888675, 0.0285449, 0.457648, -0.392391, -0.563738, -0.726794, 0.237247, -0.82546, 0.51218 +26,0,3,6.41364, -0.415533, -0.14739, -0.889434, 0.0150338, 0.456816, -0.39143, -0.541083, -0.74432, 0.235985, -0.840835, 0.487142 +30,0,3,6.41676, -0.419003, -0.149303, -0.88859, 0.02466, 0.458039, -0.392621, -0.557218, -0.731681, 0.237184, -0.83, 0.50482 +32,0,3,6.41486, -0.414786, -0.147805, -0.888638, 0.0216722, 0.458098, -0.392533, -0.552475, -0.735316, 0.237152, -0.833248, 0.499457 +33,0,3,6.41312, -0.415669, -0.149218, -0.889423, 0.0230896, 0.456502, -0.391106, -0.555335, -0.733921, 0.236566, -0.831306, 0.502958 +34,0,3,6.41581, -0.420692, -0.1493, -0.888719, 0.0202873, 0.458003, -0.391811, -0.552323, -0.735815, 0.238037, -0.833384, 0.498809 +35,0,3,6.41545, -0.417676, -0.148595, -0.889128, 0.0177028, 0.457316, -0.392126, -0.544714, -0.741298, 0.235983, -0.838435, 0.491262 +36,0,3,6.41554, -0.417827, -0.147793, -0.88894, 0.0200284, 0.457585, -0.391974, -0.550088, -0.7374, 0.236944, -0.834866, 0.496846 +38,0,3,6.4156, -0.419438, -0.149139, -0.888704, 0.0181811, 0.458122, -0.392199, -0.54766, -0.739086, 0.237458, -0.836503, 0.493838 +39,0,3,6.41592, -0.419726, -0.148205, -0.88887, 0.018103, 0.457803, -0.391864, -0.547773, -0.739181, 0.237391, -0.836431, 0.493992 +40,0,3,6.41308, -0.41398, -0.147445, -0.888795, 0.0225761, 0.457749, -0.391773, -0.555705, -0.733284, 0.237819, -0.831073, 0.502752 +41,0,3,6.41558, -0.419005, -0.150199, -0.888648, 0.0163574, 0.458298, -0.392395, -0.544338, -0.741432, 0.237341, -0.838707, 0.490143 +43,0,3,6.41319, -0.414568, -0.148718, -0.888764, 0.0166943, 0.458062, -0.392194, -0.544934, -0.741101, 0.237241, -0.838313, 0.490865 +44,0,3,6.41576, -0.417651, -0.148585, -0.888916, 0.0366866, 0.456599, -0.392435, -0.575128, -0.71779, 0.236269, -0.817241, 0.525637 +45,0,3,6.41311, -0.414883, -0.148113, -0.888697, 0.0209851, 0.458014, -0.392293, -0.55188, -0.735891, 0.237326, -0.833659, 0.498686 +47,0,3,6.41531, -0.418608, -0.14774, -0.888478, 0.0256834, 0.4582, -0.392929, -0.558401, -0.730613, 0.237095, -0.829173, 0.506219 +49,0,3,6.41452, -0.41754, -0.148803, -0.888423, 0.0207105, 0.45856, -0.392711, -0.551521, -0.735937, 0.237663, -0.833904, 0.498117 +51,0,3,6.4149, -0.418897, -0.147607, -0.888844, 0.0194535, 0.457798, -0.392258, -0.548709, -0.738277, 0.236836, -0.835787, 0.495347 +52,0,3,6.41515, -0.419103, -0.147985, -0.888158, 0.00746305, 0.459479, -0.392839, -0.531132, -0.750717, 0.238442, -0.847256, 0.474661 +54,0,3,6.41486, -0.419487, -0.147253, -0.888316, 0.0201316, 0.458792, -0.392911, -0.550491, -0.736601, 0.237732, -0.834599, 0.49692 +55,0,3,6.41548, -0.423436, -0.159608, -0.888336, 0.0117088, 0.459045, -0.392145, -0.539475, -0.745111, 0.238919, -0.84192, 0.483827 +56,0,3,6.41393, -0.413276, -0.147331, -0.888461, 0.0221725, 0.458417, -0.392709, -0.553657, -0.734333, 0.237524, -0.83245, 0.500609 +57,0,3,6.41617, -0.416027, -0.147925, -0.888416, 0.0275427, 0.458214, -0.392157, -0.564389, -0.726415, 0.238603, -0.825049, 0.512213 +59,0,3,6.41544, -0.418138, -0.149079, -0.888326, 0.0207943, 0.458742, -0.393041, -0.551039, -0.736122, 0.237478, -0.834221, 0.497675 +65,0,3,6.41485, -0.418415, -0.150333, -0.888215, 0.0241968, 0.45879, -0.393603, -0.555137, -0.732735, 0.236962, -0.831407, 0.502605 +67,0,3,6.41337, -0.413696, -0.147439, -0.889076, 0.0207984, 0.457287, -0.391874, -0.550908, -0.736841, 0.236598, -0.834307, 0.49795 +68,0,3,6.41531, -0.423697, -0.158053, -0.888764, 0.0189876, 0.457972, -0.391479, -0.551148, -0.736872, 0.238419, -0.834192, 0.497273 +69,0,3,6.41517, -0.41772, -0.14845, -0.888584, 0.0353099, 0.457355, -0.392033, -0.576149, -0.717191, 0.238181, -0.816581, 0.525799 +71,0,3,6.4146, -0.418477, -0.148934, -0.889027, 0.0166544, 0.457553, -0.391621, -0.545389, -0.74107, 0.237202, -0.838018, 0.491387 +73,0,3,6.41469, -0.415439, -0.147279, -0.889161, 0.0200506, 0.457156, -0.391438, -0.550759, -0.737185, 0.237002, -0.834424, 0.497561 +77,0,3,6.41544, -0.42462, -0.158291, -0.888708, 0.0150563, 0.458226, -0.391756, -0.544146, -0.741912, 0.238171, -0.838856, 0.489485 +79,0,3,6.4147, -0.417083, -0.15055, -0.888445, 0.0191223, 0.458584, -0.392891, -0.548203, -0.738316, 0.237279, -0.836127, 0.494561 +80,0,3,6.41465, -0.418382, -0.148101, -0.889236, 0.01238, 0.457282, -0.391718, -0.536882, -0.747205, 0.236256, -0.843566, 0.482264 +82,0,3,6.41516, -0.418368, -0.148857, -0.888409, 0.0206852, 0.458586, -0.392447, -0.552479, -0.735359, 0.238148, -0.83327, 0.498946 +86,0,3,6.41457, -0.416592, -0.146294, -0.888974, 0.0236125, 0.457349, -0.391779, -0.55634, -0.732799, 0.237138, -0.830619, 0.503822 +87,0,3,6.41461, -0.41689, -0.146885, -0.888863, 0.022773, 0.457607, -0.392123, -0.55441, -0.734077, 0.236984, -0.831932, 0.501724 +88,0,3,6.41653, -0.420248, -0.147149, -0.888439, 0.0198612, 0.458566, -0.392312, -0.551466, -0.736191, 0.238262, -0.833961, 0.497735 +90,0,3,6.41572, -0.417207, -0.148289, -0.888423, 0.0225948, 0.458469, -0.392786, -0.554273, -0.733826, 0.237536, -0.832028, 0.501304 +92,0,3,6.41419, -0.416391, -0.147474, -0.888525, 0.0132343, 0.458639, -0.391252, -0.544008, -0.742278, 0.23968, -0.838976, 0.488543 +93,0,3,6.41596, -0.415558, -0.147023, -0.888818, 0.0223397, 0.457716, -0.391997, -0.554415, -0.734142, 0.237364, -0.831941, 0.501531 +94,0,3,6.41504, -0.425882, -0.159355, -0.888318, 0.0196605, 0.458808, -0.392013, -0.552863, -0.735302, 0.239201, -0.833041, 0.498825 +96,0,3,6.41262, -0.415329, -0.148251, -0.8888, 0.0159125, 0.458019, -0.391384, -0.546317, -0.740511, 0.23844, -0.837427, 0.491794 +98,0,3,6.4142, -0.416551, -0.147325, -0.889098, 0.0157165, 0.457448, -0.391268, -0.544709, -0.741756, 0.237519, -0.838478, 0.490449 +101,0,3,6.41434, -0.41749, -0.14983, -0.888519, 0.00765455, 0.458777, -0.392802, -0.529469, -0.75191, 0.237152, -0.848295, 0.47345 +102,0,3,6.41455, -0.416019, -0.147967, -0.888105, 0.0195106, 0.459228, -0.392137, -0.553379, -0.734847, 0.23979, -0.832701, 0.499109 +103,0,3,6.41537, -0.424822, -0.158132, -0.888426, 0.0107882, 0.458894, -0.392475, -0.536295, -0.747229, 0.238041, -0.843962, 0.480692 +105,0,3,6.41514, -0.420166, -0.149923, -0.888723, 0.0209869, 0.457963, -0.391998, -0.552769, -0.73538, 0.237714, -0.83307, 0.499485 +106,0,3,6.41483, -0.410732, -0.142746, -0.888303, 0.0214411, 0.458757, -0.393, -0.55235, -0.73516, 0.237632, -0.833336, 0.499081 +108,0,3,6.41633, -0.42072, -0.148395, -0.888452, 0.0193328, 0.458563, -0.392634, -0.549412, -0.737554, 0.237681, -0.835328, 0.495717 +110,0,3,6.41464, -0.41578, -0.148714, -0.888172, 0.0201748, 0.459069, -0.392434, -0.553035, -0.734948, 0.239053, -0.832914, 0.499107 +111,0,3,6.41519, -0.41913, -0.15056, -0.888769, 0.0100065, 0.458247, -0.391792, -0.535458, -0.748187, 0.237885, -0.844503, 0.479819 +112,0,3,6.41407, -0.414732, -0.148437, -0.888478, 0.0203662, 0.458467, -0.392387, -0.55179, -0.735908, 0.23799, -0.833735, 0.498244 +113,0,3,6.41473, -0.416603, -0.151604, -0.888627, 0.017707, 0.458289, -0.391628, -0.549333, -0.738147, 0.238683, -0.835416, 0.495087 +114,0,3,6.41473, -0.417407, -0.148831, -0.888463, 0.0203053, 0.4585, -0.392329, -0.551982, -0.735795, 0.238143, -0.833609, 0.498382 +117,0,3,6.41595, -0.416439, -0.147536, -0.88817, 0.0263299, 0.45876, -0.393615, -0.558749, -0.729978, 0.237112, -0.828919, 0.506628 +118,0,3,6.41371, -0.417916, -0.150726, -0.888985, 0.00899718, 0.457849, -0.390909, -0.535688, -0.748484, 0.23853, -0.844368, 0.479735 +119,0,3,6.41568, -0.418321, -0.148144, -0.888822, 0.0185789, 0.457877, -0.391837, -0.548907, -0.738353, 0.237614, -0.835677, 0.49516 +123,0,3,6.41464, -0.425553, -0.159021, -0.888393, 0.025592, 0.458371, -0.392393, -0.560598, -0.729218, 0.238299, -0.827693, 0.508073 +124,0,3,6.41665, -0.42124, -0.147088, -0.888461, 0.0201533, 0.45851, -0.392772, -0.550195, -0.736896, 0.237419, -0.834793, 0.496742 +125,0,3,6.41506, -0.41923, -0.146857, -0.888731, 0.0184584, 0.458058, -0.391417, -0.550698, -0.737241, 0.238643, -0.834501, 0.496647 +126,0,3,6.41516, -0.417955, -0.148507, -0.888935, 0.0117379, 0.457884, -0.391699, -0.537654, -0.746659, 0.237419, -0.843084, 0.482537 +127,0,3,6.41536, -0.42041, -0.14872, -0.888422, 0.00735059, 0.45897, -0.392165, -0.53181, -0.75059, 0.238568, -0.846832, 0.475354 +128,0,3,6.41589, -0.419265, -0.148867, -0.888391, 0.0150766, 0.45884, -0.391621, -0.546447, -0.740289, 0.239571, -0.837358, 0.491363 +129,0,3,6.41391, -0.416297, -0.14678, -0.889183, 0.0210923, 0.457066, -0.391131, -0.553389, -0.735376, 0.237424, -0.832656, 0.500314 diff --git a/matlab/test.m b/matlab/test.m new file mode 100644 index 0000000..95534b6 --- /dev/null +++ b/matlab/test.m @@ -0,0 +1,140 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +%% Datasets +mocap_name = "CCW1"; +mocap_files = load("CCW1.mat"); + +distance(1,:) = [318,1834]; +distance(2,:) = [2792,5156]; +distance(3,:) = [5779,6880]; +distance(4,:) = [7422,8925]; +distance(5,:) = [9625,11170]; +distance(6,:) = [11850,13270]; +estimation_indices = 3; + + +%% Frame assignment +for k = 1:mocap_files.(mocap_name).RigidBodies.Bodies + if strcmp(mocap_files.(mocap_name).RigidBodies.Name(k),'lidar') + lidar_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + lidar_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + tag_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + end +end + + +%% Remove invalid data points +n = 1; +invalid_num = 0; +total_frames = mocap_files.(mocap_name).Frames; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || ... + any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || ... + any(isnan(tag_rot_raw(:,:,m))); + + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end + +valid_frames = n - 1; +lidart = 1:valid_frames; +y = squeeze(lidar_pos(1, 1,:)); +figure(1); +scatter(lidart,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 2,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 3,:)); +figure(3); +scatter(p,q,'filled'); + + + +%% Frame conversion +R_L1L2 = rotx(180) * roty(0) * rotz(-92); +R_T1T2 = rotx(200) * roty(-7)* rotz(-85); +O_L2_in_L1 = [0.12 0.0 0.12]'; +O_T2_in_T1 = [0, 0, 0]'; +H_L1L2 = constructHByRotationTranslation(R_L1L2, -R_L1L2 * O_L2_in_L1); +H_T1T2 = constructHByRotationTranslation(R_T1T2, -R_T1T2 * O_T2_in_T1); + +%% Mocap data +% LiDAR1 +L1_trans_mean = lidar_pos(1, :, distance(estimation_indices,1)) ./ 1000; +L1_rot_mean = lidar_rot(1, :, distance(estimation_indices,1)); + + +% Target1 +T1_trans_mean = tag_pos(1, :, distance(estimation_indices,1)) ./ 1000; +T1_rot_mean = tag_rot(1, :, distance(estimation_indices,1)); + + +% Convert rotm from 1x9 to 3x3 +L1_rotm = reshape(L1_rot_mean, 3, 3); +T1_rotm = reshape(T1_rot_mean, 3, 3); + +% Construct H +H_W1T1 = constructHByRotationTranslation(T1_rotm', -T1_rotm' * T1_trans_mean'); +H_W1L1 = constructHByRotationTranslation(L1_rotm', -L1_rotm' * L1_trans_mean'); + + + +%%%%%%%%%%%%%% +M_H_L2T2 = (H_T1T2 * H_W1T1) / (H_L1L2 * H_W1L1); +M_R_L2T2 = M_H_L2T2(1:3, 1:3); +M_O_T2_in_L2 = -M_R_L2T2 \ M_H_L2T2(1:3, 4); + + + +%% Estimated data +lidart = dlmread("tag_size1.220000pose.txt", ',', 1, 0); +L_trans_L2T2_raw = mean(lidart(:, 4:6), 1); +L_rotm_L2T2_raw = reshape(mean(lidart(1, 7:end), 1), [], 3)'; +L_rpy_L2T2_raw = rad2deg(rotm2eul(L_rotm_L2T2_raw(1:3,1:3), 'XYZ')); + +L_H_L2T2_raw = constructHByRotationTranslation(L_rotm_L2T2_raw, L_trans_L2T2_raw); +L_H_L2T2 = inv(L_H_L2T2_raw); + +%%%%%%%%%%%%%% +L_R_L2T2 = L_H_L2T2(1:3, 1:3); +L_O_T2_in_L2 = -L_R_L2T2 \ L_H_L2T2(1:3, 4); + + +%% Restuls +M_cur_rpy = rad2deg(rotm2eul(M_H_L2T2(1:3,1:3), 'XYZ')); +M_cur_trans = M_O_T2_in_L2; % -M_H_L2T2(1:3,1:3)' * M_H_L2T2(1:3,4); +L_cur_rpy = rad2deg(rotm2eul(L_H_L2T2(1:3,1:3), 'XYZ')); +L_cur_trans = L_O_T2_in_L2; %L_H_L2T2(1:3, 4); + + +disp("Translation error:") +M_cur_trans - L_cur_trans + +disp("RPY error:") +M_cur_rpy - L_cur_rpy + [90-45, 0 180] + + diff --git a/matlab/testKNN.m b/matlab/testKNN.m new file mode 100644 index 0000000..ddc502b --- /dev/null +++ b/matlab/testKNN.m @@ -0,0 +1,21 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + +root_path = "./paper_data/"; + + +angles = rad2deg(readmatrix(root_path + "angles_ours.txt")); + +%% +figure(3) +cla(3) +hold on +scatter(angles(1,:), angles(1,:), '.') +scatter(angles(2,:), angles(2,:), '*') +scatter(angles(3,:), angles(3,:), 'o') +scatter(angles(4,:), angles(4,:), 'v') +% for i = 1:size(angles, 1) +% scatter(angles(i,:), angles(i,:), '.') +% end \ No newline at end of file diff --git a/matlab/test_convexhull.m b/matlab/test_convexhull.m new file mode 100644 index 0000000..1ddf004 --- /dev/null +++ b/matlab/test_convexhull.m @@ -0,0 +1,92 @@ +P = [ + 0.968726 -0.178424 -0.871657 0.995598 -0.69754 0.777897 0.0648819 0.37225 0.374775 -0.412644 -0.00294906 -0.793658 0.618191 -0.813039 0.455101 0.375723 0.424175 -0.305768 0.823295 0.723834 0.999987 -0.860187 -0.0350187 0.997849 -0.105933 0.258959 -0.342446 -0.647579 -0.967399 0.168977 0.239193 -0.272803 0.551535 -0.0080452 0.22528 -0.511346 0.461459 0.658402 0.969689 -0.433371 0.499542 -0.800881 -0.673737 0.680375 -0.686642 0.112888 0.115121 -0.623598 -0.901675 -0.578234 0.350952 0.729158 0.333761 -0.270431 -0.466668 -0.439916 -0.281809 -0.444451 -0.00371218 -0.0570331 0.153381 -0.310114 0.766073 0.495619 -0.552687 -0.211346 -0.615572 0.0250708 0.841829 -0.29928 -0.172033 0.529743 0.271423 0.676267 -0.431413 0.958868 0.146637 0.317493 0.0534899 -0.232336 -0.0845688 -0.74905 -0.203127 0.673656 -0.327298 0.314608 -0.70468 -0.405423 -0.991677 0.666477 -0.124725 -0.350386 -0.145345 0.969503 -0.860489 -0.85094 0.313127 -0.52344 -0.012834 -0.39141 + -0.992843 -0.989183 -0.959954 -0.891885 -0.85491 -0.846011 -0.824713 -0.81252 -0.80072 -0.770664 -0.757482 -0.747849 -0.736596 -0.730195 -0.721884 -0.668052 -0.634888 -0.630755 -0.604897 -0.592904 -0.591343 -0.59069 -0.56835 -0.563486 -0.547787 -0.541726 -0.537144 -0.519875 -0.514226 -0.511175 -0.437881 -0.423461 -0.423241 -0.417893 -0.407937 -0.347973 -0.343251 -0.339326 -0.323514 -0.295083 -0.262673 -0.234208 -0.21662 -0.211234 -0.198111 -0.166997 -0.147601 -0.127006 -0.10179 -0.0522121 -0.0340995 -0.0152023 -0.00548297 0.0268018 0.0795207 0.0922137 0.10497 0.10794 0.152399 0.18508 0.186423 0.196963 0.251331 0.25782 0.302264 0.317662 0.326454 0.335448 0.369513 0.37334 0.391968 0.398151 0.434594 0.448504 0.477069 0.487622 0.511162 0.523556 0.539828 0.548547 0.561737 0.586941 0.629534 0.636255 0.695369 0.717353 0.762124 0.809865 0.846138 0.850753 0.86367 0.863791 0.868989 0.870008 0.898654 0.900208 0.93481 0.941268 0.94555 0.984457 + 0.654782 0.566564 -0.0845965 0.74108 -0.784303 0.299414 -0.479006 -0.777449 0.0616159 0.73107 -0.723523 -0.00911188 -0.896983 0.0404202 0.206218 -0.119791 0.243646 0.218212 -0.329554 0.587314 0.779911 -0.077159 0.900505 0.0258648 -0.624934 0.40124 -0.851678 0.595596 -0.725537 -0.69522 0.572004 -0.337228 -0.340716 -0.639158 0.275105 0.45872 0.480877 -0.542064 0.79512 0.615449 -0.411679 -0.396474 0.826053 0.566198 -0.740419 -0.660786 0.659878 0.917274 0.972934 0.730362 -0.0361283 -0.0726757 -0.672064 0.904459 -0.249586 0.438537 0.15886 -0.0452059 -0.674487 0.888636 0.333113 0.666487 0.0354295 -0.929158 0.021372 0.217766 0.780465 0.0632129 0.306261 0.912936 0.347873 -0.757714 -0.716795 -0.643585 0.279958 0.806733 -0.896122 -0.0251462 -0.199543 0.886103 0.384153 -0.671796 0.368437 -0.00785118 -0.130973 -0.12088 0.282161 0.819286 0.187784 0.746543 0.86162 0.816969 0.167141 0.36889 0.0519907 -0.894941 0.278917 0.804416 -0.414966 0.153942 + -0.337042 0.548772 -0.873808 -0.855342 0.294415 -0.503912 0.754768 -0.276798 0.514588 0.442012 -0.279115 0.52095 -0.893155 -0.843536 -0.0151566 0.76015 -0.918271 0.254316 0.536459 0.0960841 -0.749063 0.639355 0.840256 0.678224 -0.447531 -0.366266 0.266144 0.465309 0.608353 0.464297 -0.385084 -0.817703 -0.620498 0.368357 0.0485743 0.277308 -0.595574 0.786745 -0.727851 0.838053 -0.535477 0.31424 0.63939 0.59688 -0.782382 0.813608 -0.211223 0.837861 0.415818 -0.812161 -0.390089 0.697884 0.660024 0.83239 0.520497 -0.773439 -0.0948483 0.257742 -0.452178 -0.0981649 -0.422444 -0.532217 -0.584313 0.495606 0.942931 -0.482188 -0.302214 -0.921439 -0.485469 0.17728 0.27528 0.371572 0.213938 -0.556069 -0.291903 0.967191 -0.684386 -0.685456 0.783059 0.832546 -0.11488 0.490143 0.821944 -0.330057 -0.993537 0.84794 -0.136093 0.747958 -0.639255 0.662075 0.441905 0.244191 -0.469077 -0.233623 -0.827888 0.0431267 0.51947 0.70184 0.542715 0.755228 + + ]'; +convex_hull = [ + -0.178424 -0.871657 -0.69754 0.618191 0.495619 -0.85094 -0.012834 -0.39141 -0.52344 -0.124725 -0.901675 -0.0350187 0.995598 0.968726 + -0.989183 -0.959954 -0.85491 -0.736596 0.25782 0.900208 0.94555 0.984457 0.941268 0.86367 -0.10179 -0.56835 -0.891885 -0.992843 + 0.566564 -0.0845965 -0.784303 -0.896983 -0.929158 -0.894941 -0.414966 0.153942 0.804416 0.86162 0.972934 0.900505 0.74108 0.654782 + 0.548772 -0.873808 0.294415 -0.893155 0.495606 0.0431267 0.542715 0.755228 0.70184 0.441905 0.415818 0.840256 -0.855342 -0.337042 + + + ]; + +% convex_hull = [ +% 0.968726 +% -0.992843 +% 0.654782 +% -0.337042 +% -0.178424 +% -0.989183 +% 0.566564 +% 0.548772 +% -0.871657 +% -0.959954 +% -0.0845965 +% -0.873808 +% -0.69754 +% -0.85491 +% -0.784303 +% 0.294415 +% 0.618191 +% -0.736596 +% -0.896983 +% -0.893155 +% 0.495619 +% 0.25782 +% -0.929158 +% 0.495606 +% -0.85094 +% 0.900208 +% -0.894941 +% 0.0431268 +% -0.012834 +% 0.94555 +% -0.414966 +% 0.542715 +% -0.39141 +% 0.984457 +% 0.153942 +% 0.755228 +% 0.968726 +% -0.992843 +% 0.654782 +% -0.337042 +% 0.995598 +% -0.891885 +% 0.74108 +% -0.855342 +% -0.0350187 +% -0.56835 +% 0.900505 +% 0.840257 +% -0.901675 +% -0.10179 +% 0.972934 +% 0.415818 +% -0.124725 +% 0.86367 +% 0.86162 +% 0.441905 +% -0.52344 +% 0.941268 +% 0.804416 +% 0.70184 +% -0.39141 +% 0.984457 +% 0.153942 +% 0.755228 +% ]; +% convex_hull = reshape(convex_hull, 4, []); +[k, area] = convhull(P(:, 2), P(:, 3)); +area +cla(5) +figure(5) +plot(P(:,2),P(:,3),'*') +hold on +plot(P(k,2),P(k,3)) +scatter(convex_hull(2, :), convex_hull(3, :), 'ro') + diff --git a/matlab/test_original.m b/matlab/test_original.m new file mode 100644 index 0000000..5b4653f --- /dev/null +++ b/matlab/test_original.m @@ -0,0 +1,158 @@ +clear, clc +addpath(genpath("/home/brucebot/workspace/matlab_utils")); +addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + + +%% Datasets +mocap_name = "CCW1"; +mocap_files = load("CCW1.mat"); + +distance(1,:) = [318,1834]; +distance(2,:) = [2792,5156]; +distance(3,:) = [5779,6880]; +distance(4,:) = [7422,8925]; +distance(5,:) = [9625,11170]; +distance(6,:) = [11850,13270]; +estimation_indices = 3; + + +%% Frame assignment +for k = 1:mocap_files.(mocap_name).RigidBodies.Bodies + if strcmp(mocap_files.(mocap_name).RigidBodies.Name(k),'lidar') + lidar_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + lidar_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = ... + mocap_files.(mocap_name).RigidBodies.Positions(k,:,:); + tag_rot_raw = ... + mocap_files.(mocap_name).RigidBodies.Rotations(k,:,:); + end +end + + +%% Remove invalid data points +n = 1; +invalid_num = 0; +total_frames = mocap_files.(mocap_name).Frames; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || ... + any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || ... + any(isnan(tag_rot_raw(:,:,m))); + + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end + +valid_frames = n - 1; +lidart = 1:valid_frames; +y = squeeze(lidar_pos(1, 1,:)); +figure(1); +scatter(lidart,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 2,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1, 3,:)); +figure(3); +scatter(p,q,'filled'); + + + +%% Frame conversion +H_L1L2 = eye(4); +H_T1T2 = eye(4); + +R_L1L2 = rotx(180) * roty(0) * rotz(-92); +R_T1T2 = rotx(200) * roty(-7)* rotz(-85); +O_L2_in_L1 = [0.12 0.0 0.12]'; +O_T2_in_T1 = [0, 0, 0]'; +H_L1L2 = constructHByRotationTranslation(R_L1L2, -R_L1L2 * O_L2_in_L1); +H_T1T2 = constructHByRotationTranslation(R_T1T2, -R_T1T2 * O_T2_in_T1); + +%% Mocap data +% LiDAR1 +% L1_trans_mean = mean(lidar_pos(1, :, distance(estimation_indices,1):distance(estimation_indices,2)), 3) ./ 1000; +% L1_rot_mean = mean(lidar_rot(1, :, distance(estimation_indices,1):distance(estimation_indices,2)), 3); +L1_trans_mean = lidar_pos(1, :, distance(estimation_indices,1)) ./ 1000; +L1_rot_mean = lidar_rot(1, :, distance(estimation_indices,1)); + + +% Target1 +T1_trans_mean = tag_pos(1, :, distance(estimation_indices,1)) ./ 1000; +T1_rot_mean = tag_rot(1, :, distance(estimation_indices,1)); + + +% Convert rotm from 1x9 to 3x3 +L1_rotm = reshape(L1_rot_mean, 3, 3); +T1_rotm = reshape(T1_rot_mean, 3, 3); + +% Construct H (by moving pionts) +% H_W1T1 = constructHByRotationTranslation(T1_rotm, -T1_rotm' * T1_trans_mean'); +% H_W1L1 = constructHByRotationTranslation(L1_rotm, -L1_rotm' * L1_trans_mean'); +% H_W1T1 = constructHByRotationTranslation(T1_rotm, T1_trans_mean'); +% H_W1L1 = constructHByRotationTranslation(L1_rotm, L1_trans_mean'); + +% case 1: assume the mocap returns (R0, T0) +% where R0: R_local_from_global +H_W1T1 = constructHByRotationTranslation(T1_rotm', -T1_rotm' * T1_trans_mean'); +H_W1L1 = constructHByRotationTranslation(L1_rotm', -L1_rotm' * L1_trans_mean'); + +% case 2: assume the mocap returns (R0, T0) +% where R0: R_global_from_local +% H_W1T1 = constructHByRotationTranslation(T1_rotm, -T1_rotm * T1_trans_mean'); +% H_W1L1 = constructHByRotationTranslation(L1_rotm, -L1_rotm * L1_trans_mean'); + +%%%%%%%%%%%%%% +M_H_L2T2 = (H_T1T2 * H_W1T1) / (H_L1L2 * H_W1L1); +M_R_L2T2 = M_H_L2T2(1:3, 1:3); +M_O_T2_in_L2 = -M_R_L2T2 \ M_H_L2T2(1:3, 4); + + + +%% Estimated data +lidart = dlmread("tag_size1.220000pose.txt", ',', 1, 0); +L_trans_L2T2_raw = mean(lidart(:, 4:6), 1); +L_rotm_L2T2_raw = reshape(mean(lidart(1, 7:end), 1), [], 3)'; +L_rpy_L2T2_raw = rad2deg(rotm2eul(L_rotm_L2T2_raw(1:3,1:3), 'XYZ')); + +L_H_L2T2_raw = constructHByRotationTranslation(L_rotm_L2T2_raw, L_trans_L2T2_raw); +L_H_L2T2 = inv(L_H_L2T2_raw); + +%%%%%%%%%%%%%% +L_R_L2T2 = L_H_L2T2(1:3, 1:3); +L_O_T2_in_L2 = -L_R_L2T2 \ L_H_L2T2(1:3, 4); + + +%% Restuls +M_cur_rpy = rad2deg(rotm2eul(M_H_L2T2(1:3,1:3), 'XYZ')); +M_cur_trans = -M_H_L2T2(1:3,1:3)' * M_H_L2T2(1:3,4); +L_cur_rpy = rad2deg(rotm2eul(L_H_L2T2(1:3,1:3), 'XYZ')); +L_cur_trans = L_O_T2_in_L2; %L_H_L2T2(1:3, 4); + +% disp("H_gt * inv(H_est)") +% % M_H_L2T2 / L_H_L2T2 +% M_R_L2T2 / L_R_L2T2 + +disp("Translation error:") +M_cur_trans - L_cur_trans + +disp("RPY error:") +M_cur_rpy - L_cur_rpy + [90-45, 0 180] + + diff --git a/matlab/textmain.m b/matlab/textmain.m new file mode 100644 index 0000000..9133806 --- /dev/null +++ b/matlab/textmain.m @@ -0,0 +1,144 @@ +clear, clc +% addpath(genpath("E:/2020summer_research/matlab/matlab_utils-master")); +% addpath("/home/brucebot/workspace/lc-calibration/L1_relaxation") +loadLibraries(2); + +analyze_package = 1; % analyze each step of the pipeline +% event = 4; % which date +dataset = 2; % 1: front 2: ccw +tag_size = 1.22; +TextData = getTextData(); + + + +%% Compare with ground truth +gt_ID = 0; +gt_rot_num = 3; +num_estimates = 7; +results(num_estimates) = struct('name', [], 'distance', [], 'num_scans', [], ... + 'ID_ratio', [], 'translation', [], 'geodesic', []); +for i = (1 + num_estimates * (dataset - 1)) : ... + (num_estimates + num_estimates * (dataset-1)) + if (isempty(TextData(i).pose_raw_data)) + continue; + end + + + results(i).name = TextData(i).name; + results(i).distance = norm(TextData(i).translation); + results(i).num_scans = size(TextData(i).pose_raw_data, 1); + results(i).ID = length(find(abs((TextData(i).id - gt_ID)))); + results(i).rot_num = ... + length(find(abs((TextData(i).rot_num - gt_rot_num)))); + + results(i).ID_ratio = results(i).ID / results(i).num_scans; + results(i).rot_num_ratio = ... + results(i).rot_num / results(i).num_scans; + + i; + % translation is in mm + results(i).translation = ... + (TextData(i).translation - TextData(i).est_translation) * 1000; + results(i).translation = ... + norm((TextData(i).translation - TextData(i).est_translation) * 1000); + + results(i).rpy = ... + TextData(i).rpy - TextData(i).est_rpy + TextData(i).change_coordinate; + results(i).geodesic = rad2deg(norm(Log_SO3(eul2rotm(deg2rad(results(i).rpy), "XYZ")))); + results(i).dH = TextData(i).L_H_LT / TextData(i).est_L_H_LT; +end + +disp("===============================================================") +disp("=========== Results of Decoding and Pose Estimation ===========") +disp("===============================================================") +results(all(cell2mat(arrayfun( @(x) structfun( @isempty, x), ... + results, 'UniformOutput', false)), 1)) = []; +struct2table(results) + +disp("===============================================================") +disp("=========== Summary of Decoding and Pose Estimation ===========") +disp("===============================================================") +disp("-- mean:") +fprintf("---- Number of scans: %.3f\n", mean([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", mean([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", mean([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) +disp("-- median:") +fprintf("---- Number of scans: %.3f\n", median([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", median([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", median([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) +disp("-- std:") +fprintf("---- Number of scans: %.3f\n", std([results.num_scans])) +fprintf("---- Translation error [mm]: %.3f\n", std([results.translation])) +fprintf("---- Rotation error [deg]: %.3f\n", std([results.geodesic])) +fprintf("---- ID ratio: %.3f\n", sum([results.ID])/sum([results.num_scans]) * 100) +fprintf("---- Rotation Number ratio: %.3f\n", sum([results.rot_num])/sum([results.num_scans]) * 100) + + + +%% Package general analysis +if analyze_package + disp("===============================================================") + disp("================= Results of General Analysis =================") + disp("===============================================================") + for i = (1 + num_estimates * (dataset - 1)) : ... + (num_estimates + num_estimates * (dataset-1)) + dataset_num = i; + if isempty(TextData(dataset_num).num_data) + warning("No results for %s", TextData(dataset_num).name) + else + disp("-------------------------------------------------------") + fprintf("Each of below average over %i scans ", ... + TextData(dataset_num).num_data) + fprintf("from %s dataset: \n", TextData(dataset_num).name) + disp("-------------------------------------------------------") + struct2table(TextData(dataset_num).computation_hz) + struct2table(TextData(dataset_num).timing_hz) + struct2table(TextData(dataset_num).clusters) + + if ~isfield(TextData(dataset_num), ... + 'decoding_hz') || ... + isempty(TextData(dataset_num).decoding_hz) + warning("No decoding_hz for %s dataset", ... + TextData(dataset_num).name) + else + struct2table(TextData(dataset_num).decoding_hz) + end + end + end + + %% summary + disp("===============================================================") + disp("============= Summary Results of General Analysis =============") + disp("===============================================================") + + summary_t = summarizeGeneralAnalysis(TextData, "hz"); + disp("-----------------------------------------------------------") + fprintf("Average Hz over all dadtasets with %i scans \n", ... + summary_t.total_scans) + disp("-----------------------------------------------------------") + + t1 = struct2table(summary_t.computation_hz) + t2 = struct2table(summary_t.timing_hz) + t3 = struct2table(summary_t.clusters) + + if isfield('decoding_hz', summary_t) + t4 = struct2table(summary_t.decoding_hz) + end + + +% disp("-----------------------------------------------------------") +% fprintf("Average ms over all dadtasets with %i scans \n", ... +% summary_t.total_scans) +% disp("-----------------------------------------------------------") +% summary_t = summarizeGeneralAnalysis(TextData, "mean"); +% t1 = struct2table(summary_t.computation_mean) +% t2 = struct2table(summary_t.timing_mean) +% t3 = struct2table(summary_t.clusters) +% if isfield('decoding_mean', summary_t) +% t4 = struct2table(summary_t.decoding_mean) +% end +end \ No newline at end of file diff --git a/package.xml b/package.xml index b58fce2..b40086c 100644 --- a/package.xml +++ b/package.xml @@ -1,8 +1,8 @@ - lidar_tag + lidartag 0.0.0 - A package for lidar_tag + A package for lidartag brucebot diff --git a/preprocess/CCW1.m b/preprocess/CCW1.m new file mode 100644 index 0000000..18f4f69 --- /dev/null +++ b/preprocess/CCW1.m @@ -0,0 +1,71 @@ +clear +file = load('CCW1.mat'); +total_frames = file.CCW1.Frames; +for k = 1:file.CCW1.RigidBodies.Bodies + if strcmp(file.CCW1.RigidBodies.Name(k),'lidar') + lidar_pos_raw = file.CCW1.RigidBodies.Positions(k,:,:); + lidar_rot_raw = file.CCW1.RigidBodies.Rotations(k,:,:); + else + tag_pos_raw = file.CCW1.RigidBodies.Positions(k,:,:); + tag_rot_raw = file.CCW1.RigidBodies.Rotations(k,:,:); + end +end + +n = 1; +invalid_num = 0; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos_raw(:,:,m))) || any(isnan(lidar_rot_raw(:,:,m))); + tag_invalid = any(isnan(tag_pos_raw(:,:,m))) || any(isnan(tag_rot_raw(:,:,m))); + if (lidar_invalid || tag_invalid) + lidar_pos_raw(:,:,m) = zeros(1,3); + lidar_rot_raw(:,:,m) = zeros(1,9); + tag_pos_raw(:,:,m) = zeros(1,3); + tag_rot_raw(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + else + lidar_pos(:,:,n) = lidar_pos_raw(:,:,m); + lidar_rot(:,:,n) = lidar_rot_raw(:,:,m); + tag_pos(:,:,n) = tag_pos_raw(:,:,m); + tag_rot(:,:,n) = tag_rot_raw(:,:,m); + n = n + 1; + end +end +valid_frames = n - 1; +x = 1:valid_frames; +y = squeeze(lidar_pos(1,1,:)); +figure(1); +scatter(x,y,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1,2,:)); +figure(2); +scatter(p,q,'filled'); +p = 1:valid_frames; +q = squeeze(lidar_pos(1,3,:)); +figure(3); +scatter(p,q,'filled'); + +mocap_to_lidar_change_of_basis = [0 -1 0; 1 0 0; 0 0 1]; +new_basis = mocap_to_lidar_change_of_basis; +%CCW1 +distance(1,:) = [318,1834]; +distance(2,:) = [2792,5156]; +distance(3,:) = [5779,6880]; +distance(4,:) = [7422,8925]; +distance(5,:) = [9625,11170]; +distance(6,:) = [11850,13270]; +for i = 1:6 + lidar_pos_mean = mean(lidar_pos(1,:,distance(i,1):distance(i,2)),3); + lidar_rot_mean = mean(lidar_rot(1,:,distance(i,1):distance(i,2)),3); + tag_pos_mean = mean(tag_pos(1,:,distance(i,1):distance(i,2)),3); + tag_rot_mean = mean(tag_rot(1,:,distance(i,1):distance(i,2)),3); + lidar_rotm = reshape(lidar_rot_mean,3,3); + tag_rotm = reshape(tag_rot_mean,3,3); + world_H_tag = createSE3(tag_rotm, tag_pos_mean'); + world_H_lidar = createSE3(lidar_rotm, lidar_pos_mean'); + lidar_H_tag = world_H_lidar \ world_H_tag; + angles = rotm2eul(lidar_H_tag(1:3,1:3), 'ZYX'); + angles = fliplr(angles)'; + angles = flipud(new_basis*angles)'; + tag_rotm_lidar(i,:) = angles; + tag_pos_lidar(i,:) = new_basis*lidar_H_tag(1:3,4); +end \ No newline at end of file diff --git a/preprocess/createSE3.m b/preprocess/createSE3.m new file mode 100644 index 0000000..00304a0 --- /dev/null +++ b/preprocess/createSE3.m @@ -0,0 +1,5 @@ +function [H] = createSE3(R, position) +%CREATESE3 Creates a 4x4 from a 3x3 rotation matrix and 3x1 position matrix +H = [[R; zeros(1,3)] [position; 1]]; +end + diff --git a/preprocess/loadpose.m b/preprocess/loadpose.m new file mode 100644 index 0000000..0584cb8 --- /dev/null +++ b/preprocess/loadpose.m @@ -0,0 +1,46 @@ +clear +file = load('big-3.mat'); +total_frames = file.big_3.Frames; +for k = 1: file.big_3.RigidBodies.Bodies + if strcmp(file.big_3.RigidBodies.Name(k), 'lidar') + lidar_pos = file.big_3.RigidBodies.Positions(k,:,:); + lidar_rot = file.big_3.RigidBodies.Rotations(k,:,:); + else + tag_pos = file.big_3.RigidBodies.Positions(k,:,:); + tag_rot = file.big_3.RigidBodies.Rotations(k,:,:); + end +end +invalid_num = 0; +for m = 1: total_frames + lidar_invalid = any(isnan(lidar_pos(:,:,m))) || any(isnan(lidar_rot(:,:,m))); + tag_invalid = any(isnan(tag_pos(:,:,m))) || any(isnan(tag_rot(:,:,m))); + if (lidar_invalid || tag_invalid) + lidar_pos(:,:,m) = zeros(1,3); + lidar_rot(:,:,m) = zeros(1,9); + tag_pos(:,:,m) = zeros(1,3); + tag_rot(:,:,m) = zeros(1,9); + invalid_num = invalid_num + 1; + end +end +lidar_pos_mean = sum(lidar_pos,3)/(total_frames - invalid_num); +lidar_rot_mean = sum(lidar_rot,3)/(total_frames - invalid_num); +tag_pos_mean = sum(tag_pos,3)/(total_frames - invalid_num); +tag_rot_mean = sum(tag_rot,3)/(total_frames - invalid_num); +lidar_rotm = reshape(lidar_rot_mean,3,3); +tag_rotm = reshape(tag_rot_mean,3,3); +world_H_tag = createSE3(tag_rotm, tag_pos_mean'); +world_H_lidar = createSE3(lidar_rotm, lidar_pos_mean'); +lidar_H_tag = world_H_lidar \ world_H_tag; +angles = rotm2eul(lidar_H_tag(1:3,1:3), 'ZYX'); +mocap_to_lidar_change_of_basis = [0 -1 0; 1 0 0; 0 0 1]; +new_basis = mocap_to_lidar_change_of_basis; +angles = fliplr(angles)'; +angles = flipud(new_basis*angles)'; +tag_rotm_lidar = angles; +tag_pos_lidar = new_basis*lidar_H_tag(1:3,4); +figure(1) +vector(1,:) = tag_rotm_lidar; +vector(2,:) = tag_pos_lidar/1000; +linespec='-' + +quiver3(zeros(2,1),zeros(2,1),zeros(2,1),vector(:,1), vector(:,2),vector(:,3),0,linespec) diff --git a/rviz/LiDARTag.rviz b/rviz/LiDARTag.rviz new file mode 100644 index 0000000..aa3e4a5 --- /dev/null +++ b/rviz/LiDARTag.rviz @@ -0,0 +1,518 @@ +Panels: + - Class: rviz/Displays + Help Height: 79 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /FillInClusterB&W1/Namespaces1 + - /Tamplate1/Namespaces1 + Splitter Ratio: 0.48235294222831726 + Tree Height: 755 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /Interact1 + Name: Tool Properties + Splitter Ratio: 0.5326633453369141 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" + - Class: rviz/Displays + Help Height: 79 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 362 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Axes + Enabled: true + Length: 1 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: + Value: true + - Alpha: 0.5 + Cell Size: 2 + Class: rviz/Grid + Color: 226; 226; 226 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 20 + Reference Frame: + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/color/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 113 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: AllLidarPoints + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Points + Topic: /velodyne_points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 234 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PoI + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Spheres + Topic: /LiDARTag/lidartag_main/WholeEdgedPC + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: false + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 1 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Clusters + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Spheres + Topic: /LiDARTag/lidartag_main/ClusterEdgePC + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: false + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 80 + Min Color: 0; 0; 0 + Min Intensity: 50 + Name: FilledInClusters + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 10 + Size (m): 0.019999999552965164 + Style: Points + Topic: /LiDARTag/lidartag_main/DetectedPC + Unreliable: false + Use Fixed Frame: true + Use rainbow: false + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /LiDARTag/lidartag_main/BoundaryMarker + Name: ClusterBoundaries + Namespaces: + {} + Queue Size: 0 + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /LiDARTag/lidartag_main/ClusterMarker + Name: FillInClusterB&W + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 130 + Min Color: 0; 0; 0 + Min Intensity: 78 + Name: BoundaryPoints + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Boxes + Topic: /LiDARTag/lidartag_main/BoundaryPts + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: -0.9950828552246094 + Min Color: 0; 0; 0 + Min Intensity: -0.9950828552246094 + Name: EstimatedCorners + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Spheres + Topic: /LiDARTag/lidartag_main/TransformedPointsTag + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 50 + Min Color: 0; 0; 0 + Min Intensity: 50 + Name: InitialGuessCorners + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Spheres + Topic: /LiDARTag/lidartag_main/TransformedPoints + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 223 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: InitialTransformedPoints + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /LiDARTag/lidartag_main/Initial_Template_points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/Marker + Enabled: true + Marker Topic: /LiDARTag/lidartag_main/TagFrame + Name: TagFrame + Namespaces: + {} + Queue Size: 100 + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /LiDARTag/lidartag_main/IDMarkers + Name: ID + Namespaces: + {} + Queue Size: 100 + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: -999999 + Min Color: 0; 0; 0 + Min Intensity: 999999 + Name: PlannerTransformedPoint + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /LiDARTag/lidartag_main/Template_points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: -999999 + Min Color: 0; 0; 0 + Min Intensity: 999999 + Name: 3DTransformedPoints + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /LiDARTag/lidartag_main/Template_points_3d + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 200 + Min Color: 0; 0; 0 + Min Intensity: 50 + Name: FunctionLibrary + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /LiDARTag/lidartag_main/Associated_pattern_3d + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /LiDARTag/lidartag_main/IdealFrame + Name: Tamplate + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Global Options: + Background Color: 0; 0; 0 + Default Light: true + Fixed Frame: velodyne + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.548966884613037 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 2.623408079147339 + Y: -0.08055201172828674 + Z: 0.9260057806968689 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.12479828298091888 + Target Frame: + Value: Orbit (rviz) + Yaw: 2.9817159175872803 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1396 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000004d8fc020000000afc00000040000001710000000000fffffffaffffffff0100000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730000000000ffffffff0000009e00fffffffb0000001200530065006c0065006300740069006f006e0000000000000001560000007500fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000400000037f000000db00fffffffb0000000a0049006d00610067006501000003c5000001530000001600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000100044006900730070006c006100790073000000028c00000194000000db00fffffffb0000000a0049006d0061006700650100000257000001f90000000000000000000000010000010f000003fcfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000040000003fc000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000047700000039fc0100000002fb0000000800540069006d00650100000000000004770000029400fffffffb0000000800540069006d006501000000000000045000000000000000000000031b000004d800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1143 + X: 859 + Y: 160 diff --git a/scripts/.ipynb_checkpoints/clusterAnalysis-checkpoint.ipynb b/scripts/.ipynb_checkpoints/clusterAnalysis-checkpoint.ipynb new file mode 100644 index 0000000..2fd6442 --- /dev/null +++ b/scripts/.ipynb_checkpoints/clusterAnalysis-checkpoint.ipynb @@ -0,0 +1,6 @@ +{ + "cells": [], + "metadata": {}, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/scripts/.ipynb_checkpoints/scratchpad-checkpoint.ipynb b/scripts/.ipynb_checkpoints/scratchpad-checkpoint.ipynb new file mode 100644 index 0000000..2fd6442 --- /dev/null +++ b/scripts/.ipynb_checkpoints/scratchpad-checkpoint.ipynb @@ -0,0 +1,6 @@ +{ + "cells": [], + "metadata": {}, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/scripts/.ipynb_checkpoints/viewStats-checkpoint.ipynb b/scripts/.ipynb_checkpoints/viewStats-checkpoint.ipynb new file mode 100644 index 0000000..2fd6442 --- /dev/null +++ b/scripts/.ipynb_checkpoints/viewStats-checkpoint.ipynb @@ -0,0 +1,6 @@ +{ + "cells": [], + "metadata": {}, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/scripts/clusterAnalysis.ipynb b/scripts/clusterAnalysis.ipynb new file mode 100644 index 0000000..5d868f0 --- /dev/null +++ b/scripts/clusterAnalysis.ipynb @@ -0,0 +1,537 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 29, + "metadata": {}, + "outputs": [], + "source": [ + "import sys\n", + "import numpy as np\n", + "import os\n", + "\n", + "import mpld3\n", + "import matplotlib.pyplot as plt" + ] + }, + { + "cell_type": "code", + "execution_count": 43, + "metadata": {}, + "outputs": [], + "source": [ + "# Constants\n", + "FILE_PATH = \"../output/stats_beforeRingCheck.txt\"\n", + "FILE_PATH2 = \"../output/stats_afterRingCheck.txt\"" + ] + }, + { + "cell_type": "code", + "execution_count": 44, + "metadata": {}, + "outputs": [], + "source": [ + "class TagDetectionStatistics:\n", + " PC_SIZE_IDX = 0\n", + " EDGE_CLOUD_SIZE_IDX = 1\n", + " TOTAL_CLUSTER_SIZE_IDX = 2\n", + " REMOVED_BY_AREA_IDX = 3 \n", + " REMOVED_BY_BOUNDARY_IDX = 4\n", + " REMOVED_BY_NO_EDGE_IDX = 5\n", + " REMOVED_BY_MIN_RET_IDX = 6\n", + " REMAINING_CLUSTERS_IDX = 10\n", + " \n", + " class Data:\n", + " def __init__(self):\n", + " self.pc_size = []\n", + " self.edge_cloud_size = []\n", + " self.total_cluster_size = []\n", + " self.removed_by_area = []\n", + " self.removed_by_boundary = []\n", + " self.removed_by_no_edge = []\n", + " self.removed_by_min_ret = []\n", + " self.remaining_clusters = []\n", + " \n", + " def __init__(self):\n", + " self.pc_size = []\n", + " self.edge_cloud_size = []\n", + " self.total_cluster_size = []\n", + " self.removed_by_area = []\n", + " self.removed_by_boundary = []\n", + " self.removed_by_no_edge = []\n", + " self.removed_by_min_ret = []\n", + " self.remaining_clusters = []\n", + "\n", + " def convertToNumpy(self):\n", + " data = TagDetectionStatistics.Data()\n", + "\n", + " data.pc_size = np.array(self.pc_size).astype(np.int)\n", + " data.edge_cloud_size = np.array(self.edge_cloud_size).astype(np.int)\n", + " data.total_cluster_size = np.array(self.total_cluster_size).astype(np.int)\n", + " data.removed_by_area = np.array(self.removed_by_area).astype(np.int)\n", + " data.removed_by_boundary = np.array(self.removed_by_boundary).astype(np.int)\n", + " data.removed_by_no_edge = np.array(self.removed_by_no_edge).astype(np.int)\n", + " data.removed_by_min_ret = np.array(self.removed_by_min_ret).astype(np.int)\n", + " data.remaining_clusters = np.array(self.remaining_clusters).astype(np.int)\n", + "\n", + " return data" + ] + }, + { + "cell_type": "code", + "execution_count": 45, + "metadata": {}, + "outputs": [], + "source": [ + "def readStatisticsFromFile(filepath):\n", + "\n", + " stats = TagDetectionStatistics()\n", + "\n", + " with open(filepath) as fp:\n", + " for line in fp:\n", + " \n", + " line_split = line.split(',')\n", + " \n", + " stats.pc_size.append(\n", + " line_split[TagDetectionStatistics.PC_SIZE_IDX])\n", + " stats.edge_cloud_size.append(\n", + " line_split[TagDetectionStatistics.EDGE_CLOUD_SIZE_IDX])\n", + " stats.total_cluster_size.append(\n", + " line_split[TagDetectionStatistics.TOTAL_CLUSTER_SIZE_IDX])\n", + " stats.removed_by_area.append(\n", + " line_split[TagDetectionStatistics.REMOVED_BY_AREA_IDX])\n", + " stats.removed_by_boundary.append(\n", + " line_split[TagDetectionStatistics.REMOVED_BY_BOUNDARY_IDX])\n", + " stats.removed_by_no_edge.append(\n", + " line_split[TagDetectionStatistics.REMOVED_BY_NO_EDGE_IDX])\n", + " stats.removed_by_min_ret.append(\n", + " line_split[TagDetectionStatistics.REMOVED_BY_MIN_RET_IDX])\n", + " stats.remaining_clusters.append(\n", + " line_split[TagDetectionStatistics.REMAINING_CLUSTERS_IDX])\n", + " \n", + " return stats.convertToNumpy()" + ] + }, + { + "cell_type": "code", + "execution_count": 46, + "metadata": {}, + "outputs": [], + "source": [ + "data = readStatisticsFromFile(FILE_PATH)\n", + "dataA = readStatisticsFromFile(FILE_PATH2) " + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data.total_cluster_size)\n", + "plt.title(\"Total Number of Clusters Before Pruning\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data.removed_by_min_ret)\n", + "plt.title(\"Clusters Removed By Minimum Return Check\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 40, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data.remaining_clusters)\n", + "plt.title(\"Remaining Clusters\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "unaccounted_clusters = data.total_cluster_size - \\\n", + " data.removed_by_area - \\\n", + " data.removed_by_boundary - \\\n", + " data.removed_by_no_edge - \\\n", + " data.removed_by_min_ret\n", + "\n", + "plt.plot(unaccounted_clusters)\n", + "plt.title(\"Unaccounted for Cluster Removal\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 47, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data.removed_by_boundary, label=\"Before\")\n", + "plt.plot(dataA.removed_by_boundary, label=\"After\")\n", + "plt.legend()\n", + "plt.title(\"Remaining Clusters\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.7.5" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/scripts/scratchpad.ipynb b/scripts/scratchpad.ipynb new file mode 100644 index 0000000..c342f7a --- /dev/null +++ b/scripts/scratchpad.ipynb @@ -0,0 +1,139 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "import math\n", + "import numpy as np" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [], + "source": [ + "filepath = '../output/sample_hist.txt'\n", + "with open(filepath) as fp:\n", + " points = []\n", + " for line in fp:\n", + " points.append(int(line))\n", + "points = np.array(points)" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "50\n", + "1\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "plt.hist(points,bins=41)\n", + "plt.yscale('log', nonposy='clip')\n", + "print(np.amax(points))\n", + "print(np.amin(points))" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[2391 97 34 24 8 2 4 6 1 1 2 2 2 1\n", + " 1 1 1 0 0 0 0 0 0 0 0 1 0 0\n", + " 0 0 0 0 0 0 0 0 0 0 1]\n", + "[ 1. 2.25641026 3.51282051 4.76923077 6.02564103 7.28205128\n", + " 8.53846154 9.79487179 11.05128205 12.30769231 13.56410256 14.82051282\n", + " 16.07692308 17.33333333 18.58974359 19.84615385 21.1025641 22.35897436\n", + " 23.61538462 24.87179487 26.12820513 27.38461538 28.64102564 29.8974359\n", + " 31.15384615 32.41025641 33.66666667 34.92307692 36.17948718 37.43589744\n", + " 38.69230769 39.94871795 41.20512821 42.46153846 43.71794872 44.97435897\n", + " 46.23076923 47.48717949 48.74358974 50. ]\n" + ] + } + ], + "source": [ + "hist, bin_edges = np.histogram(points, bins=39)\n", + "print(hist)\n", + "print(bin_edges)" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "0.9868217054263566\n", + "2546\n", + "2580\n" + ] + } + ], + "source": [ + "print(np.sum(hist[0:4]) / np.sum(hist))\n", + "print(np.sum(hist[0:4]))\n", + "print(np.sum(hist))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.7.5" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/scripts/viewStats.ipynb b/scripts/viewStats.ipynb new file mode 100644 index 0000000..2593bef --- /dev/null +++ b/scripts/viewStats.ipynb @@ -0,0 +1,1074 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "import sys\n", + "import numpy as np\n", + "import os\n", + "\n", + "import mpld3\n", + "import matplotlib.pyplot as plt" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [], + "source": [ + "# Constants\n", + "CONTROL1_FILE_PATH = \"../output/Analysis_control_1.txt\"\n", + "CONTROL2_FILE_PATH = \"../output/Analysis_control_2.txt\"\n", + "CONTROL3_FILE_PATH = \"../output/Analysis_control_3.txt\"\n", + "CONTROL4_FILE_PATH = \"../output/Analysis_control_4.txt\"\n", + "\n", + "ZTHRESH_FILE_PATH = \"../output/Analysis_zthresh.txt\"\n", + "ZYTHRESH_FILE_PATH = \"../output/Analysis_zythresh.txt\"\n", + "ZYXTHRESH_FILE_PATH = \"../output/Analysis_zyxthresh.txt\"" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "class TagDetectionStatistics:\n", + " ORIGINAL_CLUSTER_SIZE_IDX = 13\n", + " CLUSTERS_REMOVED_BY_POINT_IDX = 14\n", + " REMAINING_CLUSTERS_IDX = 15\n", + " \n", + " CLUSTER_IDX_IN_PC_IDX = 0\n", + "\n", + " class Data:\n", + " def __init__(self):\n", + " # Original cluster size with thresholding\n", + " self.total_num_clusters = []\n", + " # The id of the cluster per payload\n", + " # Will be 1 for every line if only one cluster / payload\n", + " self.cluster_pc_ids = [] \n", + " # Number of clusters removed by point check\n", + " self.pt_rm_clusters = []\n", + " # Remainign clusters in point cloud after all checks\n", + " self.clusters_in_pc = []\n", + "\n", + " def __init__(self):\n", + " self.original_cluster_size = []\n", + " self.cluster_idx_in_pc = []\n", + " self.not_met_point_thresh = []\n", + " self.remaining_clusters = []\n", + "\n", + " def convertToNumpy(self):\n", + " data = TagDetectionStatistics.Data()\n", + " data.total_num_clusters = np.array(self.original_cluster_size).astype(np.int)\n", + " data.cluster_pc_ids = np.array(self.cluster_idx_in_pc).astype(np.int)\n", + " data.pt_rm_clusters = np.array(self.not_met_point_thresh).astype(np.int)\n", + " data.clusters_in_pc = np.array(self.remaining_clusters).astype(np.int) \n", + "\n", + " self.reportWarnings(data)\n", + " \n", + " return data\n", + " \n", + " def reportWarnings(self, data):\n", + " if not self.oneClusterPerPCCheck(data):\n", + " print(\"Warning, some payloads have more than 1 cluster!\")\n", + " \n", + " def oneClusterPerPCCheck(self, data):\n", + " return np.all(data.clusters_in_pc == 1)" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "def readStatisticsFromFile(filepath):\n", + "\n", + " stats = TagDetectionStatistics()\n", + "\n", + " with open(filepath) as fp:\n", + " for line in fp:\n", + " line_split = line.split(',')\n", + " \n", + " getOriginalClusterSize(line_split, stats)\n", + " getClusterIdxInPC(line_split, stats)\n", + " getNumClustersRemovedByPointThreshold(line_split, stats)\n", + " getRemainingClustersForPointCloud(line_split, stats)\n", + "\n", + " return stats" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "def getOriginalClusterSize(line, stats):\n", + " stats.original_cluster_size.append(\n", + " line[TagDetectionStatistics.ORIGINAL_CLUSTER_SIZE_IDX]\n", + " )\n", + "\n", + "def getClusterIdxInPC(line, stats):\n", + " stats.cluster_idx_in_pc.append(\n", + " line[TagDetectionStatistics.CLUSTER_IDX_IN_PC_IDX]\n", + " )\n", + " \n", + "def getNumClustersRemovedByPointThreshold(line, stats):\n", + " stats.not_met_point_thresh.append(\n", + " line[TagDetectionStatistics.CLUSTERS_REMOVED_BY_POINT_IDX]\n", + " )\n", + " \n", + "def getRemainingClustersForPointCloud(line, stats):\n", + " stats.remaining_clusters.append(\n", + " line[TagDetectionStatistics.REMAINING_CLUSTERS_IDX]\n", + " )" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Warning, some payloads have more than 1 cluster!\n" + ] + } + ], + "source": [ + "# Get data from analysis file\n", + "stats_ctrl1 = readStatisticsFromFile(CONTROL1_FILE_PATH)\n", + "data_ctrl1 = stats_ctrl1.convertToNumpy()\n", + "\n", + "stats_ctrl2 = readStatisticsFromFile(CONTROL2_FILE_PATH)\n", + "data_ctrl2 = stats_ctrl2.convertToNumpy()\n", + "\n", + "stats_ctrl3 = readStatisticsFromFile(CONTROL3_FILE_PATH)\n", + "data_ctrl3 = stats_ctrl3.convertToNumpy()\n", + "\n", + "stats_ctrl4 = readStatisticsFromFile(CONTROL4_FILE_PATH)\n", + "data_ctrl4 = stats_ctrl4.convertToNumpy()\n", + "\n", + "stats_zthr = readStatisticsFromFile(ZTHRESH_FILE_PATH)\n", + "data_zthr = stats_zthr.convertToNumpy()\n", + "\n", + "stats_zythr = readStatisticsFromFile(ZYTHRESH_FILE_PATH)\n", + "data_zythr = stats_zythr.convertToNumpy()\n", + "\n", + "stats_zyxthr = readStatisticsFromFile(ZYXTHRESH_FILE_PATH)\n", + "data_zyxthr = stats_zyxthr.convertToNumpy()" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAmoAAAGDCAYAAACbcTyoAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjEsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy8QZhcZAAAgAElEQVR4nOydeXwV1fn/3ychgSiyKhVrC6LUsCnQwFfcWk1VtKCGgkr9FlHQal1//bpTi9raqqUquNZWCypKQIiILCIIIm5JANkCsiQsCSGQANm3e+f8/pi5y9w79+YCSe4Ned6vV15JzsyceWY785nnPM85SmuNIAiCIAiCEHvERdsAQRAEQRAEwRkRaoIgCIIgCDGKCDVBEARBEIQYRYSaIAiCIAhCjCJCTRAEQRAEIUYRoSYIgiAIghCjiFAThFaGUkorpc4Js3yzUuqXEda1Syn1q0YzLsook/8qpQ4rpTKPsY6w5zeaKKWuVEp9FG07IkUptVIpNdH6+1ql1Kxo2yQIzY0INUFoIViiqE4pdWpA+feWOOh5DHVOV0r91b9Ma91Pa73yuIxtuVwMXAGcqbUe6rSCUqq7UuotpVShUqpcKbVVKfWUUurkxjLC6bo0En8DnvXbj1JK3aeU2qSUqlRK5Sul5iilBhzvjvxFVmOgtf4Y6K+UOq+x6hSEloAINUFoWeQBYz3/WC/UpOiZ0zgopdpE2waLHsAurXWl00KlVBfgG8xzPkxrfQqmsOsEnN1sVjaA0/lUSg0BOmqtv/UrngrcD9wHdAF+BnwE/DoaNkbAB8AdjW2LIMQyItQEoWXxLjDO7/9bgHf8Vwj0ZCilxiulVgdWpJS6A7gZeFgpVaGUWmCVe7szlVJPKqU+VEqlW96jtUqp850MU0rFKaUeVUrtVEqVKKVmW8LGad1fWt6bR5RS+4H/Otnp341oeZleVUottGz5Til1trVMKaVeVEodUEqVKqU2KKX6h9j3GUqpj5VSh5RSO5RSt1vlE4D/AMOs8/GUw+Z/BMqB/9Va7wLQWu/VWt+vtd7gsK+Q1yKUzWGuyxlKqblKqYNKqTyl1H1+9Xqu03tKqTJgvIPtVwNf+G3TG7gbGKu1/lxrXau1rtJaz9RaP2ut01Ep9Y61z91KqT8ppeL8j0UpNUWZXcV5SqmrrWXPAJcAr1jH8Irf9bxbKbUd2G6VXaiUyrLOQZZS6kKn62axkmYQkYIQS4hQE4SWxbdAB6VUH6VUPHAj8N6xVKS1fhOYCTyvtW6vtR4ZYtXrgDmYHpf3gY+UUgkO690HXA/8AjgDOAy8GsaE0606exC5l2Qs8BTQGdgBPGOVXwlciukR6oR5XkpC1PEBkG/ZOBr4m1IqVWv9FnAn8I11PiY7bPsrYJ7W2ojQ3nA42ux0XSxxtABYD/wYSAUeUEpd5VffdcCHVl0zHfY3APjB7/9UIF9rHS4W72WgI9AL87qOA271W/4/Vp2nAs8DbymllNZ6EvAlcI91DPf4bXO9tV1fS8gvBKYBXYEXgIVKqa4h7NkC9FRKdQhjsyCcUIhQE4SWh8erdgWwFSho4v2t0Vp/qLWux3yRtgMucFjv98AkrXW+1roWeBIYHaaLywAmW56c6ghtmae1ztRauzDFyECrvB44BUgGlNZ6i9a6MHBjpdRPMOPQHtFa12itv8f0ov0uwv13BYLqPUYistliCHCa1vpprXWd1joX+Ddwk98632itP9JaGyHOZydMb6CHsMfi9yHwmNa63PIg/hP7udqttf631toNzAC6Az8Kc8wAf9daH7Js/DWwXWv9rtbapbX+APOeDvXR4LG/UwP7EIQThliJCxEEIXLeBVYBZxHQ7dlE7PX8obU2lFIeb1QgPYAMpZS/t8mN+eJ2EpMHtdY1R2nLfr+/q4D2ll2fW91rrwI/VUplAA9qrcsCtj8DOKS19hcsu4GUCPdfgilGjpujsBnMc3uGUuqIX1k8ptfKw17CcxhTGHpo6FhOBRIxz4+H3ZgePQ/e66G1rlJKgXVNwuBv5xkB9Tvtwx+P/UdCLBeEEw7xqAlCC0NrvRszqeAaYJ7DKpXASX7/nx6uugh2+RPPH1YX3JnAPof19gJXa607+f2001qH8vgF7ttmt1IqnN3BlWk9TWv9c6AfZnfiQw6r7QO6KKX8BctPidwruQxI88RpRUDYaxHG5sBzsxfICzi3p2itr/GvrgFbNlj78LAcOFMpFUqkFmN6/Xr4lR3NuQplj3/5voD6G9pHH8xkDycxKwgnJCLUBKFlMgG4PER24vfAKKXUSVYg/oQw9RRhxh+F4+dKqVFWF+YDQC1mrFwgbwDPKKV6ACilTlNKXdfQgfixHuinlBqolGqH2XUaEUqpIUqp/7Fi5yqBGkxvng2t9V7ga+DvSql2yhzqYQLOMV1OvAB0AGb4HeePlVIvKOdhI0JeiwZsDrwumUCZMpMvkpRS8VbiwZAI7QZYhBlnBoDWejvwGvCBMpM7Eq1zcpNS6lGrO3M25jU9xTrePxJ5TGQk99Yi4GdKqd8qpdoopW4E+gKfhFj/F8DiCPcvCCcEItQEoQWitd6ptc4OsfhFoA7zRTmD8CLkLcyg7iMq9ECo8zFjlQ5jxieNsuLVApkKfAwsVUqVY4q5/2nwYCy01tuApzG9VtuBoEzVMHTAjNk6jNl1VgJMCbHuWKAnpjcnAzNO7rMIbTwEXIjpafrOOs7lQClmckMg4a5FOJtt18USTSMxY/LyML1d/8EM9I8IrfVaoFQp5X9N7gM83a9HgJ1AGmbiAsC9mCIyF/N6vA+8HeEup2LGKB5WSk0LYVMJMAL4P8zjfxgYobUuDlHnWOBfEe5fEE4IlNaR9HwIgtAaUUo9CZyjtf7faNsiHD9KqSuBP2itr4+2LUeLUmok8Dut9Q3RtkUQmhMRaoIghESEmiAIQnSRrk9BEARBEIQYRTxqgiAIgiAIMYp41ARBEARBEGIUEWqCIAiCIAgxygk5M8Gpp56qe/bsGW0zBEEQBEEQGmTNmjXFWuvTnJadkEKtZ8+eZGeHGmJKEARBEAQhdlBKBU6l5kW6PgVBEARBEGIUEWqCIAiCIAgxigg1QRAEQRCEGOWEjFFzor6+nvz8fGpqaqJtyglLu3btOPPMM0lISIi2KYIgCIJwQtBqhFp+fj6nnHIKPXv2RCkVbXNOOLTWlJSUkJ+fz1lnnRVtcwRBEAThhKDVdH3W1NTQtWtXEWlNhFKKrl27isdSEARBEBqRViPUABFpTYycX0EQBEFoXFqVUIs28fHxDBw4kP79+zNmzBiqqqoAaN++/THVt3LlSkaMGHHcdk2fPp177rkn7Dpbt25l2LBhtG3blilTphz3PgVBEARBaBgRas1IUlIS33//PZs2bSIxMZE33ngj2iZFTJcuXZg2bRoPPvhgtE0RBEEQhFaDCLUocckll7Bjxw5bWUVFBampqQwePJgBAwYwf/58AJ544gmmTp3qXW/SpElMmzYNgLKyMtLS0ujbty933nknhmEAcNddd5GSkkK/fv2YPHmyd9usrCwuvPBCzj//fIYOHUp5ebnNhoULFzJs2DCKi4tt5d26dWPIkCGS0SkIgiAIzUiryfr056kFm8nZV9aodfY9owOTR/aLaF2Xy8XixYsZPny4rbxdu3ZkZGTQoUMHiouLueCCC7j22muZMGECo0aN4v7778cwDGbNmkVmZiYbN24kMzOTnJwcevTowfDhw5k3bx6jR4/mmWeeoUuXLrjdblJTU9mwYQPJycnceOONpKenM2TIEMrKykhKSvLuPyMjgxdeeIFFixbRuXPnRj0/giAIgiAcPa1SqEWL6upqBg4cCJgetQkTJtiWa615/PHHWbVqFXFxcRQUFFBUVETPnj3p2rUr69ato6ioiEGDBtG1a1cAhg4dSq9evQAYO3Ysq1evZvTo0cyePZs333wTl8tFYWEhOTk5KKXo3r07Q4YMAaBDhw7efa9YsYLs7GyWLl1qKxcEQRCE1sCOA+WcfVr7mEuMa5VCLVLPV2PjiVELxcyZMzl48CBr1qwhISGBnj17eoe7mDhxItOnT2f//v3cdttt3m0CbyilFHl5eUyZMoWsrCw6d+7M+PHjqampQWsd8gbs1asXubm5bNu2jZSUlEY4WkEQBEFoGWTmHeKGf33DX67vz+8u6BFtc2xIjFoMUVpaSrdu3UhISGDFihXs3r3buywtLY0lS5aQlZXFVVdd5S3PzMwkLy8PwzBIT0/n4osvpqysjJNPPpmOHTtSVFTE4sWLAUhOTmbfvn1kZWUBUF5ejsvlAqBHjx7MmzePcePGsXnz5mY8akEQBEGILnsPmaMwrNt9OMqWBNNkHjWl1NvACOCA1rq/VdYFSAd6AruAG7TWh5VSvwTmA3nW5vO01k9b2wwHpgLxwH+01s82lc3R5uabb2bkyJGkpKQwcOBAkpOTvcsSExO57LLL6NSpE/Hx8d7yYcOG8eijj7Jx40YuvfRS0tLSiIuLY9CgQfTr149evXpx0UUXeetIT0/n3nvvpbq6mqSkJJYtW+at69xzz2XmzJmMGTOGBQsWcPbZZ3uX7d+/n5SUFMrKyoiLi+Oll14iJydHukkFQRCEFk9iG9NvVes2omxJMEpr3TQVK3UpUAG84yfUngcOaa2fVUo9CnTWWj9iCbUHtdYjAuqIB7YBVwD5QBYwVmudE27fKSkpOjs721a2ZcsW+vTp0zgHFwUMw2Dw4MHMmTOH3r17R9uckLT08ywIgiC0PpZs2s+d763hir4/4t/jmj/8Rym1RmvtuOMm6/rUWq8CDgUUXwfMsP6eAVzfQDVDgR1a61ytdR0wy6qjVZGTk8M555xDampqTIs0QRAEQWiJtLU8anWu2POoNXcywY+01oUAWutCpVQ3v2XDlFLrgX2Y3rXNwI+BvX7r5AP/41SxUuoO4A6An/70p01he9To27cvubm50TZDEARBEE5IPF2f9THY9RkryQRrgR5a6/OBl4GPrHKnFEXHvlqt9Zta6xStdcppp53WRGYKgiAIgnCiEWeNiBCLHrXmFmpFSqnuANbvAwBa6zKtdYX19yIgQSl1KqYH7Sd+25+J6XETBEEQBEFoFLTlA6oTjxofA7dYf9+CmemJUup0ZQ3wpZQaatlVgpk80FspdZZSKhG4yapDEARBEAShUfDkVcaiR60ph+f4APglcKpSKh+YDDwLzFZKTQD2AGOs1UcDdymlXEA1cJM201FdSql7gE8xh+d424pdEwRBEARBaBQMS6nFolBryqzPsVrr7lrrBK31mVrrt7TWJVrrVK11b+v3IWvdV7TW/bTW52utL9Baf+1XzyKt9c+01mdrrZ9pKnubg/j4eAYOHEj//v0ZM2YMVVXmAHvt27c/pvpWrlzJiBEjGl6xAaZPn84999wTdp2ZM2dy3nnncd5553HhhReyfv36496vIAiCIMQChuVRyy2uZOGGQhZuKGRXcWV0jbKIlWSCVoFnCqlNmzaRmJjIG2+8EW2TIuass87iiy++YMOGDTzxxBPccccd0TZJEARBEBoFw29M2bvfX8vd76/ll1NWRs8gP0SoRYlLLrmEHTt22MoqKipITU1l8ODBDBgwgPnz5wPwxBNPMHXqVO96kyZNYtq0aQCUlZWRlpZG3759ufPOOzEM02171113kZKSQr9+/Zg8ebJ326ysLC688ELOP/98hg4dSnl5uc2GhQsXMmzYMIqLi23lF154IZ07dwbgggsuID8/v5HOhCAIgiBEl6Ya/L8xaJWTsrP4Udi/sXHrPH0AXB3Z7FYul4vFixczfPhwW3m7du3IyMigQ4cOFBcXc8EFF3DttdcyYcIERo0axf33349hGMyaNYvMzEw2btxIZmYmOTk59OjRg+HDhzNv3jxGjx7NM888Q5cuXXC73aSmprJhwwaSk5O58cYbSU9PZ8iQIZSVlZGUlOTdf0ZGBi+88AKLFi3yijIn3nrrLa6++upjO0+CIAiCEGMYsRea5qV1CrUoUV1dzcCBAwHTozZhwgTbcq01jz/+OKtWrSIuLo6CggKKioro2bMnXbt2Zd26dRQVFTFo0CC6du0KwNChQ+nVqxcAY8eOZfXq1YwePZrZs2fz5ptv4nK5KCwsJCcnB6UU3bt3Z8iQIQC2eTpXrFhBdnY2S5cuDTt/54oVK3jrrbdYvXp1o54bQRAEQYgWhnjUYowIPV+NjSdGLRQzZ87k4MGDrFmzhoSEBHr27ElNTQ0AEydOZPr06ezfv5/bbrvNu401qont/7y8PKZMmUJWVhadO3dm/Pjx1NTUoLUOWt9Dr169yM3NZdu2baSkOM9ztmHDBiZOnMjixYu9QlEQBEEQWjqxLNQkRi2GKC0tpVu3biQkJLBixQp2797tXZaWlsaSJUvIysriqquu8pZnZmaSl5eHYRikp6dz8cUXU1ZWxsknn0zHjh0pKipi8eLFACQnJ7Nv3z6ysrIAKC8vx+VyAdCjRw/mzZvHuHHj2Lw5eASUPXv2MGrUKN59911+9rOfNeVpEARBEIRmxYhdndZKPWoxys0338zIkSNJSUlh4MCBJCcne5clJiZy2WWX0alTJ+Lj473lw4YN49FHH2Xjxo1ceumlpKWlERcXx6BBg+jXrx+9evXioosu8taRnp7OvffeS3V1NUlJSSxbtsxb17nnnsvMmTMZM2YMCxYs4Oyzz/Yue/rppykpKeEPf/gDAG3atCE7O7upT4kgCIIgNDmx7FFTsZzpcKykpKToQBGxZcsW+vTpEyWLjh/DMBg8eDBz5syhd+/e0TYnJC39PAuCIAitj4/X7+O+D9YFle969tfNsn+l1BqttWPckXR9tgBycnI455xzSE1NjWmRJgiCIAgtkVh2WknXZwugb9++5ObmRtsMQRAEQTghieWuT/GoCYIgCILQqonlcdREqAmCIAiC0KoRj5ogCIIgCEKMEsM6TYSaIAiCIAitG/GoCQDEx8czcOBA+vfvz5gxY6iqqgKgffv2x1TfypUrGTFixHHbNX36dO65556w68yfP5/zzjuPgQMHkpKSIlNICYIgCCcMsTzgrQi1ZsQzhdSmTZtITEzkjTfeiLZJEZOamsr69ev5/vvvefvtt5k4cWK0TRIEQRCERkE8akIQl1xyCTt27LCVVVRUkJqayuDBgxkwYADz588H4IknnmDq1Kne9SZNmsS0adMAKCsrIy0tjb59+3LnnXdiWKkrd911FykpKfTr14/Jkyd7t83KyuLCCy/k/PPPZ+jQoZSXl9tsWLhwIcOGDaO4uNhW3r59e+88oZWVlSHnDBUEQRCEloaMoxZjPJf5HFsPbW3UOpO7JPPI0EciWtflcrF48WKGDx9uK2/Xrh0ZGRl06NCB4uJiLrjgAq699lomTJjAqFGjuP/++zEMg1mzZpGZmcnGjRvJzMwkJyeHHj16MHz4cObNm8fo0aN55pln6NKlC263m9TUVDZs2EBycjI33ngj6enpDBkyhLKyMpKSkrz7z8jI4IUXXmDRokV07tw5yO6MjAwee+wxDhw4wMKFC4/vhAmCIAhCjBDLXZ+tUqhFi+rqagYOHAiYHrUJEybYlmutefzxx1m1ahVxcXEUFBRQVFREz5496dq1K+vWraOoqIhBgwbRtWtXAIYOHUqvXr0AGDt2LKtXr2b06NHMnj2bN998E5fLRWFhITk5OSil6N69O0OGDAGgQ4cO3n2vWLGC7Oxsli5daiv3Jy0tjbS0NFatWsUTTzxhmydUEARBEFoqTl2fp7SNDYkUG1Y0M5F6vhobT4xaKGbOnMnBgwdZs2YNCQkJ9OzZk5qaGgAmTpzI9OnT2b9/P7fddpt3m8AuSKUUeXl5TJkyhaysLDp37sz48eOpqalBax2yy7JXr17k5uaybds2UlIcpxvzcumll7Jz506Ki4s59dRTIz18QRAEQYhJnDxqsRK3JjFqMURpaSndunUjISGBFStWsHv3bu+ytLQ0lixZQlZWFldddZW3PDMzk7y8PAzDID09nYsvvpiysjJOPvlkOnbsSFFREYsXLwYgOTmZffv2kZWVBUB5eTkulwuAHj16MG/ePMaNG8fmzZuDbNuxY4e3D3/t2rXU1dV5vXqCIAiC0JIJjFE77ZS21MdIf2ir9KjFKjfffDMjR44kJSWFgQMHkpyc7F2WmJjIZZddRqdOnYiPj/eWDxs2jEcffZSNGzdy6aWXkpaWRlxcHIMGDaJfv3706tWLiy66yFtHeno69957L9XV1SQlJdm6L88991xmzpzJmDFjWLBgAWeffbZ32dy5c3nnnXdISEggKSmJ9PR0SSgQBEEQTgjcAaLsRx3aUlJRGyVr7KhYznQ4VlJSUnR2dratbMuWLfTp0ydKFh0/hmEwePBg5syZQ+/evaNtTkha+nkWBEEQWh+vr9zJc0t8SYYDf9KJ9flHyPv7r5tl/0qpNVprx7gj6fpsAeTk5HDOOeeQmpoa0yJNEARBEFoigfFo8XGx02MkXZ8tgL59+5KbmxttMwRBEAThhCSwdzFeqZiZ/1M8aoIgCIIgtGoC8wbiYkgdxZApgiAIgiAIzU8sd32KUBMEQRAEoVUT6FGLjyGXWuxYIgiCIAiCEAW01vg70eJjx6EmQq05iY+PZ+DAgfTv358xY8ZQVVUFmBOeHwsrV65kxIgRx23X9OnTueeeeyJaNysri/j4eD788MPj3q8gCIIgxAKG1sT5jQ0qXZ+tFM8UUps2bSIxMZE33ngj2iYdFW63m0ceecQ2M4IgCIIgtHQMjU2oef6OhbFmRahFiUsuuYQdO3bYyioqKkhNTWXw4MEMGDCA+fPnA/DEE08wdepU73qTJk1i2rRpAJSVlZGWlkbfvn258847MQwDgLvuuouUlBT69evH5MmTvdtmZWVx4YUXcv755zN06FDKy8ttNixcuJBhw4ZRXFwcZPPLL7/Mb37zG7p169Y4J0EQBEEQYgBDa/wn24klj1qrHEdt/9/+Ru2WrQ2veBS07ZPM6Y8/HtG6LpeLxYsXM3z4cFt5u3btyMjIoEOHDhQXF3PBBRdw7bXXMmHCBEaNGsX999+PYRjMmjWLzMxMNm7cSGZmJjk5OfTo0YPhw4czb948Ro8ezTPPPEOXLl1wu92kpqayYcMGkpOTufHGG0lPT2fIkCGUlZWRlJTk3X9GRgYvvPACixYtonPnzjbbCgoKyMjI4PPPP/fOFSoIgiAIJwI60KMWp7zl0Z4tsVUKtWhRXV3NwIEDAdOjNmHCBNtyrTWPP/44q1atIi4ujoKCAoqKiujZsyddu3Zl3bp1FBUVMWjQIO+E6EOHDqVXr14AjB07ltWrVzN69Ghmz57Nm2++icvlorCwkJycHJRSdO/enSFDhgDQoUMH775XrFhBdnY2S5cutZV7eOCBB3juueds84wKgiAIwomAYQQmE4hHLapE6vlqbDwxaqGYOXMmBw8eZM2aNSQkJNCzZ09qamoAmDhxItOnT2f//v3cdttt3m0CJ0ZXSpGXl8eUKVPIysqic+fOjB8/npqaGrTWISdS79WrF7m5uWzbto2UlODpxrKzs7npppsAKC4uZtGiRbRp04brr7/+qM+DIAiCIMQSgTFqnU5KiKI1diRGLYYoLS2lW7duJCQksGLFCnbv3u1dlpaWxpIlS8jKyrIF82dmZpKXl4dhGKSnp3PxxRdTVlbGySefTMeOHSkqKmLx4sUAJCcns2/fPm/XZXl5OS6XC4AePXowb948xo0bx+bNm4Nsy8vLY9euXezatYvRo0fz2muviUgTBEEQTggMrcHPj9H5pEQAop9K0Eo9arHKzTffzMiRI0lJSWHgwIEkJyd7lyUmJnLZZZfRqVMnW/fjsGHDePTRR9m4cSOXXnopaWlpxMXFMWjQIPr160evXr246KKLvHWkp6dz7733Ul1dTVJSEsuWLfPWde655zJz5kzGjBnDggULOPvss5vv4AVBEAQhivj3N8VSMoGKhdTTxiYlJUVnZ2fbyrZs2UKfPn2iZNHxYxgGgwcPZs6cOfTu3Tva5oSkpZ9nQRAEofXx5MebyVhXgNvQVNS6+OMVP+OFz7ax82/XNItoU0qt0VoHxx0hXZ8tgpycHM455xxSU1NjWqQJgiAIQkvE47T65rHLWT/5yqDyaCJdny2Avn37kpubG20zBEEQBOGERGMOw3FKOzOJIHY6PsWjJgiCIAiCEFPizJ9WJdRiwYV5IiPnVxAEQWiJhHp9xcJbrdUItXbt2lFSUiJioonQWlNSUkK7du2ibYogCIIgHBUa+zijMTTebeuJUTvzzDPJz8/n4MGD0TblhKVdu3aceeaZ0TZDEARBEI6aGNJmNlqNUEtISOCss86KthmCIAiCIMQYIbs+Y6ATrtV0fQqCIAiCIDjhyfr0EGq6xWggQk0QBEEQBMGh81PHQDqBCDVBEARBEFo1sdDFGQoRaoIgCIIgtHJ0TGV6+iNCTRAEQRCEVo+TTosFT5sINUEQBEEQWjWBgiyWvGtNJtSUUm8rpQ4opTb5lXVRSn2mlNpu/e5slSul1DSl1A6l1Aal1GC/bW6x1t+ulLqlqewVBEEQBKF1onVsiTN/mtKjNh0YHlD2KLBca90bWG79D3A10Nv6uQN4HUxhB0wG/gcYCkz2iDtBEARBEITGQsXokLdNJtS01quAQwHF1wEzrL9nANf7lb+jTb4FOimlugNXAZ9prQ9prQ8DnxEs/gRBEARBEI6ZwGE4Ykm0NXeM2o+01oUA1u9uVvmPgb1+6+VbZaHKg1BK3aGUylZKZcs0UYIgCIIgREpr7fo8GhyTLcKUBxdq/abWOkVrnXLaaac1qnGCIAiCIJy4hBQcrTDrs8jq0sT6fcAqzwd+4rfemcC+MOWCIAiCIAhNQix515pbqH0MeDI3bwHm+5WPs7I/LwBKra7RT4ErlVKdrSSCK60yQRAEQRCERsHs+owhdeZHm6aqWCn1AfBL4FSlVD5m9uazwGyl1ARgDzDGWn0RcA2wA6gCbgXQWh9SSv0FyLLWe1prHZigIAiCIAiCcMyEmtMzFub6bDKhprUeG2JRqsO6Grg7RD1vA283ommCIAiCIJDBuIYAACAASURBVAg2/B1qseRbi5VkAkEQBEEQhOgQwnHWGpMJBEEQBEEQYgpNgEcthlxqItQEQRAEQWj1xNIgt/6IUBMEQRAEoVWjQ/RxxkDPpwg1QRAEQRBaN0FdnzHkXROhJgiCIAhCqyd2pJkdEWqCIAiCILRqQmV3huoSbU5EqAmCIAiC0Koxuz59PjXJ+hQEQRAEQYghYkib2RChJgiCIAhCq0ayPgVBEARBEGIUDTHrUhOhJgiCIAhCq8dJp8VALoEINUEQBEEQWjkBgkzFUDaBCDVBEARBEFo1Gh1T4swfEWqCIAiCILR6HGWadH0KgiAIgiBEl8BYtFjyrYlQEwRBEAShVaN1bA1y648INUEQBEEQWj1OE7HrGOj7FKEmCIIgCEKrJlCQxZJ3TYSaIAiCIAitGun6FARBEARBaGHIgLeCIAiCIAhRJlCPxZJzTYSaIAiCIAitGrPrM5bkmQ8RaoIgCIIgtHoc5/psdiuCEaEmCIIgCEIrJzDrM3a8ayLUBEEQBEFo1YTK+tQxkE0gQk0QBEEQhFaPv1CLIYeaCDVBEARBEFo30febhUaEmiAIgiAIrRqtdYgppKKPCDVBEARBEFo9tq7P6JkRhAg1QRAEQRBaPGVVtZSs/Sqo3G242V+5P+y2seA5C8VRCTWlVJxSqkNTGSMIgiAIgnAsfHTH7zjw24lUffq+rfyltS9xxYdXcLDqYMhttQ4xjloMKLgGhZpS6n2lVAel1MlADvCDUuqhpjdNEARBEAQhMs45uAuAui3f28pXF6wG4EjtkfAVxGjaZyQetb5a6zLgemAR8FPgd01qlSAIgiAIQjMRA46zkEQi1BKUUgmYQm2+1rqe2D4mQRAEQRBOcL768lt+uDMN7XLZyg/VVzJj84yjqsvM+nQojwG5E4lQewPYBZwMrFJK9QDKmtIoQRAEQRCEcLSbfCfGyq1UffJfW/nbB79jSvYUyuqOTqrEatZnm3ALlVJxQJHW+sd+ZXuAy5raMEEQBEEQhFC0cbkB0K46W3mtrjfLGyMTIPoOtfAeNa21AdwTUKa11q4QmwiCIAiCIDQ7KoSqikSwBWZ9xlAuQURdn58ppR5USv1EKdXF89PklgmC0CgsTktlS3KfoPLHvnyMQe8OioJFgiA0Jv95/Am2JPehNvtzW/n8HfMZMGMApbWlUbIsOgRGm3nizJxmHvBHxZI68yNs16fFbdbvu/3KNNCr8c0RBKGx6blln2P5J7mfNLMlgiA0BcnrPgOg6vP5tE253Fv+3pb3ACioKKBj245RsS0a6BB6K5wQC5U0EAM9nw171LTWZzn8iEgThBZGYGaUIAgnBsrq2lPxdt+LoQ0A4lV8yG0/nzGd3Cf/EFS+pmgNi/MWN6KVzc/RxKgFdX3GUDpBJAPenqSU+pNS6k3r/95KqRFNb5ogCI1KQMCtIAgnBh6hFhhY5RFq4ej+9+eonbUiqHz8kvE8vOrhRrHPidyCYnJffTqovKKugq8KgqeBOhYMGj5+f2K05zOiGLX/AnXAhdb/+cBfm8wiQRCaBG24G1yn3m1QuC4TXVsTtGxfxb7GyaISHCnMy6N2366g8tLaUirqKprfIKHlEef8So9TweVHyio5vDErqLzeXR92qqWC7TuoL9oTVH645jBV9VURm7r17huoffkDKtJftpU/vvpx7lx2Z4NzczqhAponj1D1dGuGa79CLYqFJi8SoXa21vp5oB5Aa11NbA0xIghCJNQ37FF76e2POTL2FvY/cKOtfP3B9Vw19yrmbZ/XVNa1akoqajlyzdXkXn510LKLZ13M5XMud9hKEEy82Y4BQs0jVJyE2tfjrmX/mHFB5Y9++WjI+21XcSVlI0ey4xdXBS27NP1Srpt/XcQ2d60yxzhzHyy0leeV5gFQ5Ypc9GEEqCntLMzCedg02tbdGUvetUiEWp1SKgkrpk4pdTZQ26RWCYLQ6Gh3fYPrFGzcAED1xp228m2HtwGwsXhj4xsmcLiqPnQENFDtqm5Ga4SWhjdGLYRQcwqi73GgMKgM4LPdn4Xcz74j4e/Do/GCeSVUSFdWxFUFYx1uYNdvgz0CMSTO/IlEqD0JLAF+opSaCSwHHmlKowShtfPRu+lsu6gf7qLdtvLvD3zPLYtvoT4C0RWEu+Guz3i35XVrY28aXIbLKo4kUbz1MH/SQ2wf/vOg8oztGTzx1RMR1yNdysLx4O3yi7MnDXi6/OIieNVr4+jiuY4fUxUF3vseUfnd5D+zPe2ioK3e2fwOz2U+Zy+MC1RYVt0Bai9czF5ovRj9ZzOSrM+lwChgPPABkKK1Do48FIRj4OvVWWy7a1RQRuLe8r1HPVfbicSP3puCu8SgfNZrtvLJX09m7YG17C7bHWLLMLgaFndtXKazXMXbGz6PMEyISzj6/Z7A/GzuJ7h2BXfR/PnrP/PRjo8irif6rwKhJePr+nROJohofDC3K/J1G4GQQ2hYImvgp2twbTkUtPwf2f/wDjviUKv9v4Au0PBdn4FZn7FDJFmfy7XWJVrrhVrrT7TWxUqp5c1hnHB8rF36KcVLZgeV7zyyk51Hdjps0fwkTr4D94otVH30b1v57UtvZ0r2FI7UHImSZdHF+4WsQgzcGGFjml9S7tvWzwtX53aOV/N41FS8/cu83hChFo7jHfrEEI9ak6C15rtZ71G55ougZesPrj+mgPVYxNf1aX9u3YbBebkGJS/+NchjVhE4Yof1IRduWIomuUub4N73iMAgYdZQz2csqTM/Qgo1pVQ7awaCU5VSnf1mJegJnNFcBgrHRp3LIOm+Bzj4wOSgZdfPv57r518fBauCSfDM1RaQkVheZwqMWB0puulxFmSeL8NIx/hZcu8E3z/1PqH24poXHddvZwmywK5Pj1CL9a7PWpebA2u/cezGKawwY3KK9uyhpiAvaPlxZVce59AnotOahtU7iunw5DPsufnOoGX/u+h/+fW8X0fBqsYn1Idd5eFK/pRukPTBasr/+zdv+ebizexPCPA+eTxqUfYlHev+3YbmpGp7+LzHo1hYWWj735EWmvX5e2ANkGz99vzMB15tetOE46HFfKGH+BL0CpJWKtS8Rx3q+CM8Ld2qD3v/9hfDe8v3+sr97pVES5CpeGehlhAf2x61l597lZLf3sbhv9hfzMv3LOfKuVeyJHcFh399JXmp1wRte/Gsi7kk/ZJj2q+OoFs57PYt5HFtaRyuCn9d6owTY2zBUFmfuHzCxFXkSx4orSsN7nr03MPN1OR6p3kKEaN2tEybu5qEgy6rbk/Vmh2Hd1DrNgXcCZf1qbWeqrU+C3hQa93Lb1aC87XWrzSjjTHLzE++ZktyH0r++aCtfFfpLgbMGMB3hd9FybKW0/D7gmADspWOcqDCExaHtHo4iq9Ov9Zmx69vYP+fbrVtP+ZLN1v79PVmeiVaSQM58bX8/F1fkLx/1+d/np/GluQ+VC+zd6t/sfcLBswY4PVcRQNjm5m1Wrlug618c/FmANYXbUbXhz53nqSJo8bt4vMRFzvOqXrv5/dy5YdXht08FgKWY5GMb7ezJbkP+x+7xVZeXF3MgBkD+HTXp47bfZS5ky3Jfej5rwds5SXVJQyYMaDFj7gfRIhkAiNwYDHPag7tio7AK9wk75UGKo00yWHj1uC4XUMb7Kv0TaHXUNKOkziLhSczkqzP/UqpUwCsGQrmKaUGH89OlVL3K6U2KaU2K6UesMqeVEoVKKW+t36u8Vv/MaXUDqXUD0qp4AFcokTmZ2ao3pGMJbby7KJsABblLWp2mzy0FI+a90swICbKO1BhCzmORqehGLVj/Owt/fgb2/9jVpv1zdlqiq4EbQqVvXH1Nm+DR8Dkf7mei95+HYCKhR96l2fvz+aez+8BYOuhrcdkW3NQ526aDwCjvo7uO0ocl63cu9Lb9RKK1nqbO5Hx1nS2XdIf4/ABMr4y76UjC74ja38WE5dOxG24vWNtzdo6y7GOOV/9AEDiF3bBnluaG3a75mLBA3c4ZjS+m/NucEZjBIQaniOUzFC+lteHu+EYtabA7Xaz4rfXkHf3KMflH2yeGVE9Oi54mqxvJ/+JhAcf9f7vea+8s/kdpq2dZt8+4IREuwvYn0iE2hNa63Kl1MXAVcAM4PVj3aFSqj9wOzAUOB8YoZTqbS1+UWs90PpZZK3fF7gJ6AcMB15TKszEZc2J5zoGum5DpB03J+6W0vJ7Zj4J0fXZWvE2oyGmhIm0eyDkWQzc3BIwHo+a27ocq5evYtt9N1BvfW1fON8XlL1el3r/fvRLX2PYNr5tRLZFg3p36Puqc7nm+q+NoC/43CO5fLD1g7D1llce3zhn7sABO2OIr7/8lm1/+E1wZnbZXt7Z/E6j76/ney/iPuim8pN3aBNnnRcDHvriIb4r/I5DNYe8c1eG9oA6Px+x8vI9Z8mXjhmNz2c9HyajETbv2k/OxGtxH7InQRjWk+4OaBdUiHZUoYJOka5v3hg1bdl6pKqO09fmUbN8i7n/gGOYEqFwdRJq5y9ZQ6fvfeEfnvbzH9n/4N8b7Qlsmtjq7vQnEqHmCWz5NfC61no+kHgc++wDfKu1rtJau4AvgLQw618HzNJa12qt84AdmCIv6mirsagGDtX4HjrPjRbN7owIpniLCRoaUdvzO+vDWZRnBicbbyrexL6KfUHl4fh+5UoOLAz+SttVuosfDv1wVHU5se6zzxyzbXOP5B51tm1R1hqqN3wdVL7+4Pqw07yEJMQtqawx1hKsLk6X1eZ1ePJu3Es30n7rdmtF3zbL6/IdRz4PjGMrq6ln0+vP4S4Ovk4r9qzwdqs2Ds4H6HkW61zOY8lprfm/eW5++4VB3ZrPbctGLxjN3777m+N2Ho5UHJ9Qc8WwUGv35ztxf55D1SL7cDm3fnor/8j+B98s/YQDi4M9VLmluWw/vP3od+jnTW5rhUBow57x7ElqCSXUHPxFUSNr/jxKv3Luas37br5jeahne9WkP6JWb+fgw7fZ108w7+vMilxbub9Qq1i73lfupEgiGJsxGu+0OId32c/yNfW5m3wFhg41exYAbeusYToasN9JpP7ny1wqa48vq/t4iUSoFSil/gXcACxSSrWNcLtQbAIuVUp1VUqdBFwD/MRado9SaoNS6m2lVGer7MfAXr/t860yG0qpO5RS2Uqp7IMHj+EFdhwUxBncstgXQxELHrVY6Po8WLifytwtQeWV9ZWU1premFADNfrP0bZ2z2Ha/+kp8sfdE1TX2IVjuWru0fWGt73rTkr+L3i62pEfjWT0gtFHVVcgLrdBu3vvc8y2vW7+dRFn23rOi/vrXHbd4Mvc9NxTk1ZP4jcf/+a4bLXtz/Ii/chKPnBZT3i8JWwOVAd//dfH+3n4/Bq4xHj7d9zzb8wlfup08sfbp5f5tvBb7ltxH6+sa76QV6euz6o6F4Vrv6S9Z3pTqxtea83+yv0RCcmySt/cqGVVtXQtNa9TwfYdJNWYf9cb9RyoOgAEz4sYyx61Nh5xG+BR82Rmd7rvIUr+31NB21330XWM+ti5Oysc/ok0bZURWGra5BFq2vkFGhfBvLYeCr/PcpzbtrCi8Ljb8B0Hymn/yCT2Tfij4/KaWx51LA/1bCdq817UdYGTA5l2ugKEiL9Qq9xU4rCF3/+e4TkcMs3Lqmo5tD445tpluCiqLHK0tSG0w18QPDhvG4dL+dd33eT9xq+tNgy0qgzYga/ezhWeIm17nv2fwaBrbZ2G/361q0UItRuAT4HhWusjQBfgoWPdodZ6C/Ac8BnmjAfrARdmd+rZwECgEPintYmTMzLo6dFav6m1TtFap5x22mnHat5R4XHdomFX2a7g5VH8qouFrs+i0ansuSa4oR4+dzgXz7rY/CdE1qcnmUBrzaGKRs7MCjNVz/HSeO/b8J4hgMO1hx3XORaU282u4krO3l0AQF1Acuemsrwgq+rbOGfnxgdEJhwsNsfCq9tvH/qirNac629PWfAEz8dO+C6v+vrgVn/GA/dTevPvOcPSoqqNKTSnb57OFR9e4V0v3Eu7otLX4C+6dQyvv+bmJwc1ZSNHMuNFc5/PfvcsqXNSqair4NL0S20fBbEs1ELFkTZ1+6ZsQi3QJvN6hvKotSGyF+tJNZojN41j3132D6gfDv3AlXOv5P2t7x+FxcGUVgfbEYn4a+jZDtIUoaoMsUChgpvBEDFqhjZYdNsNFN04npM32Hs1ns18ll99+CvK6srC2utshLmfwEscKBTjQhybu9pvPcNNnN81j9Oaa7/zbdjJ0nAGBn/55i/e8pJqn3gN2/UZ5S7RSITaqUA2UKuU+imQABxXtLDW+i2t9WCt9aXAIWC71rpIa+3WWhvAv/F1b+bj87gBnAkcXV9XUxHiqsbCkBKx4FGLL3FuZI/UOgxiG/gS8IwojW7UbqGm9nLGWvaeDmx06xW1a1cENcbfF61nX3kJuo0laKzL4Vmr2xHN7L+7OGOfTzTXt4E1B9YwYMYA+n+xl9l/d5FYr21jFf0z+59sOd30mLkqYGvfZO8yj1dk2Z5ljMwY2SjH2xCqOthz8tN99uZMJZhC7bv9dg+C8xhM1ojnft6m89eb3X2nH7LfC7O3md3hFfWmYPUfIiWUUIuJWM1QiS1NZpvfcDH4hLVnfy7D5b0WoYRafISxH20t50rlml228qIq00v0ZcGXEdUTmuBzFElz9sbLLnb+ekhQ+YYf5Tiu79FjgTFpcSHOg9M7KtQQM4Y2SN5vfqglFuywLVu6aykANa7g5ypywp+Q+AgupdaaeOW7V5SG/rt89Sa4rOdUG3y+1xfa0FKGZ4lEqC0EPrF+LwdygePKbVZKdbN+/xRzeqoPlFLd/VZJw+wiBfgYuEkp1VYpdRbQG8g8nv03Fm483T52YiFgNdJp2+b943m2pQ5k0b0T2D7aN4bU8j3L+ePKP/LO5nf4Z/Y/w9QQOdV1blbcch3XfeMzztPAvJf/GXO3zfWWewSP1rpRvQ1N7bhorHdXqC/kxng5Vi3zTW3kuRJxGoqq9uFpNL1fsdbv3vvMP9rU+e5tVzx8tssc1iPta7Om9tV2QTN983S7/YZve//Bc5080sdDqLMUVx9BPFyIIVHCiXDtEPsW6gXjJC5cIR5Yt468C6+p8HjUgrzeTRUIa53mghf+xS+/e8ev2Fzw4BcPsjJ/JWCey48fvp/t1w2zVRFnnbeG/Gqe+zwwPOvkhJMBjn0AZI/NDrdMqGvtT5cKqNsZ+b697UVgYlu4ZIIgw5ynkHJrN/FWyIC7bZJtWY27hu4lmoPDLyep1r6vtUVrmfjpxJBiOqQTMMC2+IBHwPGYDIM4v/LA9tMT5xbYfvrbFqLn09Gm5iaSuT4HaK3Ps373xvR0rT7O/c5VSuUAC4C7tdaHgeeVUhuVUhuAy4D/Z+1/MzAbyMHsKr1b6xhovYC6RGv0/MAL7EkmaMKv4ZVzPmTnY7fayr768lu+mXgl87fMsXnU9pbvZdqa1/nqgVup+tqusfumv427oJazPvsa16Zib/kDKx7gs92f8Y/sfwS9bI8WTxZdXnElp3+3jZtXGiiPYrLs/GT/Nzz5zZPB26IbtRu3sbuYtNYsm/I39r1uutP9z/vyPcv5tvDbY63Z9p8n6y5QLBzTfKj+DbH1Z7xhintPN4Tvnjb/GJnpfN48XiLv2iqyF3hVnYuil16hV2FwvTO3zGRX6a4G6whk+WvTuKxgrWWIr/yrgq9Ylb8K8CVNAKyYdD+HMv7jC2GwWLznc7Ye2hrUODs+z55VHMagCiXUnMRXqPuyOYVadZ2bVQ/fSdln6fYFlmmFAd1xTe09NioUZ6z1Bcd3KK5lxHcG6w+u5431bwBmjFrvj5fi+sHupfd41IKyIAP+98Y/Gc4v4lOycyl49cmg8uW7l/P1vuAkn0CczlBjz32+etlKflLgVSLe8tzSXAycPUZKOXR9hojrM7RBnCXUXIkne8u37C1m5OcVTFhqEHfAzfm55r6r6qt4ed3LZpbu/u8anKarocSPwOfIKbkAw008do+aP20M37H4P9f+MY5m12eoXrKwJjY5R50UoLVeCwT7ZI+ujku01n2twXOXW2W/8xOF12qtC/3Wf0ZrfbbW+lyt9Qk2UuGxcfpTf6Iu41tvyrzWmlMev51Oq/cyPeMpm2C46ZOb+Pem1+iy5Ft232YPanU1xw1YZ7rFE/wm+u5gJcn5XPbOmxrawN2ILVtjdwnnH67mx/95l9KpZiyL/wv3gRUPcPvS24+p3qDwkc9zqFo4PejlOCV7yrHFh1h4czm05W1s4Hr4499gejwTcTpYXDjFmLzy+Q76f7KRZ6fb16036nk281nGLR5n/u82WPP2q2xbMp+CmfYJUb7Z9w25R3JZf3A9WmvOmPY67fODsy/vXHYnPxw2s3n9hdrpc5dS9Fiwt3hqzgzGLBgTHKsTbhBmd/BLzvGFArgDXogbvvmWuM+Dh//IL89nU/GmoPKm4o0vdnLax19QcO+Tjssnb3vX9n8kQk1pzc6Xnwwa2qPOXecVz0HbhKjrgVnljPvcoEuZb782j0i9T5TEedqMUJ5pa4HThwLAugPrALjv/cOUvZwetPyBlQ/w+89+bytbu2w5B5eY665ZtJBDn38U5KXZdngbudYYcMeFX8WdJt/tWH7TJzeFjO8yx1Gzn+ltK1dwZNUnQff91kNbcVvD2hh+J3TxpIcY/ZXmvF32nfx74795c8ObHKg+QLxbc2B68ERGFXUVlHtUcgNt8k8PalvWrH9ygWfsam0YxPl1ffbY56LbEV+9nmdx3YF1ttCbQG9fjIao0eDEfUop/zd7HDAYaN60yhgl9EVt+uE5tEdhueqgTRtKq+tJPFSPRtHGsH+1hX2Rh/lU6FqmKTkleJ3CikK6t+/uvJGTrTVVqHYn2bodA19iHmGgtabWZXj3XbK/CFXosz8nbwM9dAL6zJ/YHrKq+irqjXo6tu0Y1pbG9qgVHy6lnd//jVa9Uz1ul6NXp9ZV6zhgTllVLV1qgq+9Eae8QbRamfuKM+xCLU5DvFsTV2OgQ3zPxRvQpUxzqIPyXr94t/kSPlh1kNNOMpN6AkWfNgyq6py/3j3XtLze9Fa/tGwbI55/BTdQBpwxajwq6WQO1Rzijs/u8G73/e82ONQWjIogG9DpiehapjHcbggxgqN26N4J9ZIMzCJN/MN4Tq8O3uvV865uyNRGpSbE0CWem6I6MJ4ngnv9svWausXpHKk+TOeHp3rLX1zzIu9teY93rn6HQd0GRWRfgnWKPXFlJ9VoEgxf9qOrrISErt05UnMEcI6ZCszI/3/zndX01LVTHctD4XIbJN1zD8WAyr6ek/74IEWAXmTvfPJkcwYP3nPstKl1+03H5CuvdlVzUrhrFHDLxb8xi0Jm0f6PJ+NWmtpEc4U/ZIzjv9aQia563/k+rdae7empzj/2Mu1rTdLqj6g49XTqr5lA6apP6PGrkUz+bjI92ldyFqADPPCBXq2H5xrsm/tHOm41nwf/d8fOJDfngZlM4PeBePk6e50ej1rg2Gm2j6YwU1lFO+48Eo/aKX4/bTFj1a4Lu0UrwfPQh4wnaobAck8AaJ3b8F7NpFpt9xxpHfKrJVQCZM/9mtdfdXPlWvt2S3ct5cq5V0bk9vfuo9ZMufG3KTAGynMODW3w+p//yuuvuvnFRo0eexPn/tH3Qt56+43suWYUF826yDYv49XzrvZlkoahsbNhD91/g+3/xuvudqpHOd5T1S7nMbwWj/8Np+UGJ258ciSHDcV2YRPvFWpWPJKGexcY6JrQTcS13xm88aqb7iXaJ9QM+Mu3f+HyOZd759cLej7qQwfweoSa59naXVJlW+6ZOLrWFTj5cmTnPc5BjARu6fXyWo1z9xLzWTjylH3+0FX5q3B7Xk8OgdiRxqhpB5EWU3g+ogIHSI2gffNk29UX5NvKCyrM7OJDDsO+hKLeciskWqdv+otupj7n646tOmIKh0vSL+GHpP+Ereto2+ZAj2AglbW++6ra7yOkqd4Atnr97jMVIHpCfSyE45UXKvnHW75j+O9Lvr/nH/J5tlLWO3sG/af16lhlGlC3cysfP/Z/VD/0FIV/mkBhZaH3GNbWFti2bygerI1j16dBXIgMYQiOc/Ng88gS2m8R7Sc0khi1p/x+ntFaz9RaH0+KxwlDnHcMKWeaKkbN5TcW1A8pF1D46O9wuTXEm/trVwcjF17gZ2fkD+wn6/awJbkP931s3tnn5psbHqk5woAZA/jrt+b4YzsO7whZB9iPXdeYQsIm1DyH4HkpWv8a2qDjro0AJOdr4gMcQn3yfesBTP+ni3s/dtsGHAYYMGNA0BQhAIafyyvSOeTC8eP9dudyY3nUHMekqa1xbPmrXdVMf+9jtiT3ofyd573l5x7YG7wysLX6gK9Oa0dx2jo3fsL5f7Y21CVh/u69zy7UPC/hvWV7vXXbjqMmYLwjP4ICjwOvkdvF29PncSTlcgbt8C2LVKhpB49aYBeQV6hZ5V3LLY9S9kbbetsObfeJF3fwizyUUKsz6vjNaoPZf3d++ae8lxLK/KgSeIYDYxFr6t2su+x8tv3cl9nrtt4w88pybWNNhh0HLcS1rLWGjEkMoZmqy3z3db0yG47GapuNkgLHck89FXU+o5bd64sd7niN7+Nxw3m+8+LPluQ+FDxwg+Oy+TucB8S1G+fXpgUlEwTYa/gGEg93Bk53SMwH2FOT77wgBBVWd0PReysxDpte/PrCIjokdvCuU+Y+Ojnh+FwZBorQiUKhnsVli1eZ7ebMFwDf/bK5eDNPbbqauLaxMcBESKGmlFqglPo41E9zGhmrxHk+Zaw7vt5tHzCwqTxqVQFjQZUuyDKFWpy536QAh0WcEXyjdi3T/HBxf+Lr7DZO/2YlAGdaw8u4rK/Y3eW7Ad/4PoGDmgbi314UPv9YUFmc7M1HmgAAIABJREFUhiW7luA5ed73nZ/7OpLhzk6qg0s2O5/nQDc3BHR9ul18/OECfrikP6599q/DnJIcbl1yq9crFIpAGyMVDB+98E+2/jyZbRf3x+0nqFbsWcGVH17JrnbBjY5R6dyFXe2qpmD5QgCOzPXPnG3YZs86T73nRtVU2bo+3Q1M1Haovfm7+yGf1PG/zzyZnEEvi5qKkBHVgR61uIAXuXbXc2iFeayXrzcrHpBnsPua4LDZRbmLePzLx21lcQ6xZIEECst6a8gSI+C5S/B7BpwEYKgYtWpXNTd+aS7cdX/wC7rWXcucbXMatLPZiNCjVlZTT7vCOtyVvhUN6w1T5q6l42fZ7LzdHIbFM9ae23Dz1sa3ePK/D/HDZefhLtwV0ow6r0fNvl/Paa4p9SVDhYzNstrmo81YdRfudiz3eLP9B0S9YJtzN3xCXegGrWzJRsfyd3Kcp+iyNTPuUAscvNnWB4WhjWMaTvJoPXQVSb6dtHP7Xkwd2nYIOeBtQx41J9FV8GI6p1WEHng3lFBTX30BQNn8DNup+yT3E3O7k82ZZGI5mWAK5qCzoX5aPZ50YM81rHJVWf/b4wVWps9m56TgoPKNBzfy8tt/Crlswc4FjvutDojv0dpM+dbWizVIqOngl8avMw2MYjcqoNulqM2Htv8942ltXvYlV2f5KvEItZySHDK2ZwTZ6C9YKpZvDSqLs+buC0wm8G9AIwlodyLc17Kt69NVT6e3/4Zx0E35DPst/fQ3T5NdlN3wFDhBc3H66h+yzaD/ruAW4uOdH9Prg3+jKxXuYjfl77/sXXbfivsorCyk0qFFdFeU216O3Q5rrsk0qHJVebPcKn4oY+1vLiAjJz1MEGVw1mfHKjhlx3rv21hp3+wEofB8Lber812rNm68X8uekeuDhVo1cW7n7k+vULNsbBM4boLb7X0xe47iobkG7j3B3b+PfPkIC3Ltz5CjUAuV6eUZJNd6BnR9QNyL8hsV2KFrLNTLwb+ruvpT5xf009887bxxM+Eu8hcmvgtYF+K6hazHL6v4rkUGdV/uwH1gL/HWUB9u7ealtS9x6pKFGIX17Jh0N4kHnF1mNQlmZYkBt4TnNs3duJEf7hqFMrRj26ENw9s2hE0MccBV5OxJ8gSml9f42RzupX60njxt2P4OFFcut2HLWP3RnEzbVG1BplhC7VidCKG6EENR5Tftb9caM9BNazgl4RSvcUFewAZUUSgbLl73VehtQlzuTnXWO7tDezTau2/PddXuk8zlMTw8Rw5wUGv9hf8PUGwta/XEebxB1n3maYADkwlOf+YJ6uauRtfY423unTWWXz0/l7q59oDTXaW7+O2i3/L4ars3wEPQdBbanCtQW1mV7Rw8amcW28tCiaD4gIfG85I6/7lXuHWZQUK9uTwhznxJ3fjJjfz56z8H1ePUBWhLJggRo9YYwxGE+1r2d+RoVx1trBe3atvOtp7Hk+Y5zpAEehn8jvGhuQZ//iDYlkmrJ3HILwM2eDoY5+tTX15uO7Y/f+Bm/HKDmqK9tjGEkjaX8tnbT0fUFPuvU98mwXY93A0INc81VH72xhu+htdzLYO6PmurHIWa23AHedQSAmLRzFgwe2yo88gKzkevwkzK7iGU10C77NcyIS7B9+IMtDNMPaFiCn07Ct7w9EOaI6s+CSr/4dAP7C5z9vYcD/vv+x0ApVX1xFthYHEa3t/yvmViZC96j1f2ZL/erdo1K2mjTPeYZ0otz3k0vrbPVemPx6PWNkQP12nTMzBWbGHQTh30AQiw8aWHbXMId6x0PgZP173tOA4WOqzpe6H7t8k6zHMTqts2FP7n2d6umeVV9W7bvM5Jh+HgI755QIPaEc9A4scYluMYH2bRvhr67Anwdvo9m52rzA83DZx60qneJ7Q6ILnmWDxqEN5bHm9AnKH5+XbD9nx1sKYOKzjJalOscu/MEEYitgVRIlxT/DLgNBfTmcDRpcScoAQ2xF6hFtj1ad2t7mLfw15WVcvrr/purIrqOg5tyMRluBj5kW+UdkMbQePQBGXMaYXL7Wuc2tXbDetQrfj7jIaHTDDL7eu54s1u0rga8xjiDWjj0qh9hd5G1mtXfZWVcWV5lgJaCcdkggD8G6NjnekpnFAL9KjFW8pNJdq7cj2ZeYETjDe878gawDibYIys9XZV2mO7TrK0QWlNBX0DBoxtY4QLZPYTiX7n2BXfxtf1ScNdn55jUNpX44+OaK+3wpNR1T5Al7irq0nYFTzsRL1RT0Gl/SXZJqDrWbvdwfeFw30S6tiVQyxZ0DoBG3teDDqgyy0hLtE3vMlRJBP4zy/ohNOzMe1fbgrvCJ65b/SC0YzIGBG2vmPBqDWF9D+n/MtbpjTU5O5EGwbL9iwL3sjP7oJtW2lbp71i/xebfAtrivK9MWovrX0pYps805qFEmrxNb7lXRzGik14cyHlq0wPq6EN/v5fe1tXsDUH40gxw+cO95Z5PELVB5xjlTztne3jOYxH6OSjjO4u9YuN8xdX9VYbt6/wQFBDaVTVeN9FQR9JbhcH9hVSt29Pgx9yTgPLOs276eH2Tw2emukm3u3czp9UbT7LGvt8nlV+2cTVe3ai0XQud7Zuf+X+0N2YDvP4eog3zAzURz40+PkOTVKt5qQaTTsrsWmeazd16iAuKqiqr/INdGwlKMRy1+cAy4NmQ2v9KZgZsa2duIBbPdCj5sX6EjRKfA/74vFjbKvMvetWim64hTf/Pd5W/tr3r3HFh1fYxFqNw3yFLsMg0Dvl4ZXXg19OoTxqbQJu9l9s0jZBGW/Ag3MNzr79RVLnpNrWHbNgjDcT00mw6ICuT7PQ+t/PC3O8z0Q4r5wtmcBfqAV41Dzxhp4v/1AEx6hFZqN/A6brgr1LTufAXVXt2GWxbeFyzt5iFziGgvI2odS43779duQ2tPdjU2lTpIfD/+vacz/du8DgzELzeDzX4S/v2a/HJ99s5dq3Xwiqb3fZbu+4c56PnfhAz1tgVyghPGqhYpQcLlBgidJWsLtfogWADvDGKf8T6TDgbbgYtXAca5d/Y+I5pdX7fF1+PynW/OLhDzn09O8dJ+Jevc83LlrZtWm88rrb0Sv79taFtlkpIqUhj5qy+ll/v9gUDE5M3WnGcBra4NRy+7Ky63/Djl9dYiurtoTavF3OWe4ez0tlte+DItwH5klhQl4rPgj2f7z2jwpyS00vo3+7tsplJk9VTgwW6Vob/HbhbwHnGLWStMvpevMTDX4Ij3AY5Dohgm9K/7bN9rfHwWAYtm7cer/j2nXlCI4UlvOvV4Kv3/bD27niwyuOWah1KzWN6VAFb73kZvqLbq8YNbPea1mr7mP43OG+d5WK7mTsHsIJtXCuhKNzM5ygxFlRnKcfgdsXu1EXmWPkeFq5T3d9ysOrHqbQCqh0H/Z5oH520N5dkbzPHJBz7w57r/LyPeYkuKW1pd6yOocbst6tvS+hUC8If0I9o09Nt9vVKSBBr40bBlsjUM/+u4t2ftOG7Ck3J9ceMGOANdRDYPyW7+/Ark+v89Hfo9bQQYQgrEfN3whXPXGW10e1O8m2nmcOuAZjOQJj1CJUarYG1GlaI6cYG7cLV7WL/8/edYdJUaT9X3X3hM0ZWNKSc5AgIIiAgIoCZkwoRgyYzvAJZzz1zKdnONOZ9U7PU08xY845goJZVERB4sKyuzPT9f3RXd3V1VU9PWFhUX7Pw8NOdXdVdXXVW2+98cFLrX/F9ulcWyUPcZAMsePzd5ipZg+zn85Gjc0zTRCe1qy2xlTFMC/9zpuE/cFLk5j4kelJI7UpuQkD7x6IdaZ3PVDTjRnlxN6TNSI5At9zVRIzb/dniuj1udc7llDLVu7lH18GwK0n4XWS1HQWEpGorw1uLjx4aRJHPZty3i0IYdZvS0CmctI5tdSxT9t2kO9+JP22n6/2SknLGuTq8zXr1mDZmiY8eGkS+79qr78Qy4aRk3S5HwsDzOgcplsh+U4JkjjGHI5bsBbf7jnKd//c1+biqveugpngGTU1BzT1XbW375Uv3Sot/3mDdcDn6dpGezIWLvOL6GjKxNdrv8a+r5u4+jbhO5kpYJ3vESn6/OgfozlPpp+cvA0Z/12JremhqZTHRjAheHonN8jFjj/VW4cGNaOmnkSiXZuowuUlhWu4DBzEDqLbmsNzfEUI2V0sJIRMgZXv8w8PXjQ8+WN7EppWigo9RXHuv1P48o2nHPG5uXol1jWtw8ynZqJZoEyGrf5KCAdNluyWN7CUBW1NCaEV0vddXl5eLy93+ilMcMbIidHWRYnaF0P7IP74jb7219i2WsO/ojj9kZTXmSCoI5TitEf8m8XbS5biuanbo+cyb/sbmjdg1tOz8NMGl0mgiWYnh53KRi3IluP5Nz4FWeNeXzJuIOiXH/juO/CuvfH52AGoXieRKAJoaPYSJs2kDjPMI5FKgG7yU9m4JC4ZJeG8Pj2DnEx4nAnS2ajJJGoAMPNZqz8qhjne5NdL7fGeKWVgViYFD7pU0mXU7CKZZKDhi3WY+aJ3fkgcaaUY87mJOY+nAEpxyqMpDP7Oeo9ECrjyvSvRlGrCiS+ciC9Wf+6MMZFI1ER7pF3tmIQbs1B9bm44Kl1JIF+aSEnzN8ocDWRzqKSB4svl1hzY/w2rJdFBIAjlGykuvtttPzjQhBdOMPyQz/DfoukLd+3xTO3dn98NGpJRm/iJut0DX5Wvl3/f+Cd8tccIX59lTlyAS7OYZzGPL6dOULYvYlOwY78SuoIuUOb1mvTS+YQvk4l8/JgDCmO6REl6kEQtkqKY8KlMmm49Y6S8o+v8YoxaKw54+ycAfyeE3EUIOcn+dzcs+7RTNk/3Wjd0meeQbQPTaSUwcCnFsU+nnAmfWvMbnlv6HD5Z+Ql+EzgepnJM6N4JwYgfTwSTkpPD+88/D7qRhTQI7vd235gY+k12u4F4MqEEGLXYxKr5d3jLhaExGwiMf/zL+e0mybX+3+N9ipFfUNQ3NmPEUkuKMunjYCurUV/4r996z53otdTESfO9HX31p1fx4YoPcd8Xrs3Nx2++7XiYEYNLEL7ue8djMcg7bPHNV3p+01+ToDdc4Luv8/tfgqxMYdo7bl38N/pu02q89fo7+PLE/QFK0UmR9+OHRL1UzReV2LhRKNMXeqRNnhHkVLBhVJ/OXKDe96ncYGU1UEnUCpr8cdQaI3JJU8wUOpFMwmT9p0DXX6iTjkzE9Heym+N7vkMxbhFFaQMwZjHFPm9a9RhJgsab78RHP7yFV356BQ98eZ/DJJIn/LHmVWoidvhSIWj9bnxVHleLSV1ygYx5iUi+oZlMSb+tLJSNuOfWxy1nJ16CURYtz8jIftJHFL2419UykHdEbDvDsOE5VNJNFl7EAScVD2LU0kGX0PaTHt6A5Df1vj7LnLgAS6KmAl0V3gZ4UwzovCLzNcQzap65bBOk5iVrUfjJIqd9KggeIor+szHXHXMZIM6Fl9ICJGqiZohhE7FNXFKA/GjbyiVqlNIvAQwE8AqALva/VwAMsq/94SFGgQbgRChnkzWluW7lqXVrHcmT+OF1O2K6YU+2qvUU3X+maLSDATLivnT9Uvyw4RtfsxNuO5/rV3C///ygieos00OKYmeTAKc9amLVXMvmqPvP1Eq3Qym+Csgy5XgMCn29+aUvoa1OTxxU75iMW0mDRcJfYBQAgDOeAFBw3WXci7gVHve8G4E+SKIWlUgVzA1+aQmLJSXLjQkAZjKJ2LnHIvX8Ihz6ounYUohoSDZLN3EZowbihkYIgiemGue5GCaOGpsLsmbarPVLWRkKmv0Staaon1Eb+pWJQkHSsuTN11HX8JnT7uV3yttgqPuVomZtdgxbh1X+sv3eoNh4z42+8spfw9vzNEqkbzyC1u+Px50lLf/LW38JrDNbxCVSMpo0serLb9FDkFrLJGr8u5jE+s7RJBDhPGijegyREM7ejvQyzX3NAeZvjEEMzaiFnDpeiVq4Z2QIsmEzqRmqP9SkocKApLsjqQFX3R7iwwgY+D1F0aZgM5zRl73qyTPMI6pguFy7Vfc6z7DL7E8ZVOpStt+KThKM7juqzy3MqQVadFJKmwDcuZn6stWBSCgqTTajfulSxGx9vElcdeaa9avdtDrCc5p9iogkLI8XZsB/2DkW8WtKNeGXjb84Hl6+8zunEWtJY2RxQlcIey7zLv1h+Mt2sEN5Z2IJipIG/yKtbwyXUkb1jnHd4opENVfcsFSbPKPGd43yNhOcwXoQo2ZIoqqbDX5pCVP/eAxrecKRSCGSsOqa9i5Fr2XyNjfUb/CFXgEAItkgNRMo2iQnsg2KWFi8nVUYGzVG/GRMf806iuUb5SEN4k1+ZrbJIB5Grf/3JuY+ZGJZF2+cMeOKmzGM/Qgxz6+8wxqDGfMyN16vVjDMjWtWW8fWNFBJiRoloTx4EApU1FOsLbakM5on8rx7H88YxXWv6l6FFcuWoYQ2o6BjV6sviRQ2LP4Q8T590Wy634USy8OuUBI1niYpdr/wUezVTDzjmpA4evBzPqkDzbo1Lrz9nqEZoRg1RjSL03hO1hcAVQoTjkiGjJqYlaihOYnGJR8iuimBCAE2xSwzF/3HJc49Skl2CBQ2+gP6Mvyy8ZdQ9ovUNANVrGER1lRAxCnzTXxVC5x9uBG4F1XYUi5xD6hYJ0+LwMKmqEKExOspVGy8ylu1ap3pXOclyr822M4yrcSZIHPqtQ0OxFAWAPDYB0vR/7hr0Nve5FKay6jd8cs7eOz99wBIGLUkBQVB+eokbnnCrZcxFu/98p5H0hPcr8zeIxOIi+Tie+UrIHrEKShr5y0zidu3cx+wDZOF/eXdTReE6ofqHQvscRdtXmK6ZSjYxKmdklEDUZZ2hBO3l8ZKscJOsxSk+jQkEiNzk9orUeUNRVMpj71jmUJMP+jzJC6WhMxaCz/jc8TzpvJ0btmEWAPFDyNJeBm1dDZqjFGTqdEjKVjR9SWMbizh32mbot78newAULZWTShb+pAbUzXdEE56otoc0mW7aL8a+Os9Kfx7nIZHRxMc9oI7B5e0J/hp6XOYXDcZJ790slNeV1oXWCdgObqsnj4RqzYS9F2yGABw67xzMfmJ/+Hve2p4sy8By5PwM03gmIcm42itq68emjIRlUTZbxaTtsN7oEpqVoiNaNIK8QNYWQV0YiiZk2zgMWAXqs3FRg0A7jtpDsa+8irughVj8pD/M3DcUyYGLHLNIL6Lp9A3824DsJwNdv1I3rf95u+LXdmlgO5Tk6LdmhDvl2YByQ6FYdFlhbeJZsN/cBm9WC51O/0RuQ0nCwKtVEcn1C+kkm53tCXhhglQbj9fucm2P3GcCVqvjdo2pIV/MXQ7zwoUyRgaU3NtfWKJgMVjz5EOK+XU/b1f3wvdq5JNUHoW5YpMIlMXCPuR7KQpEtKwpzjVYo3ZNn6qU1dTypXaNEVd5+Ufz78RA22j8Yp4BUZ/bnlnzXpgH3yz1lU137bwNtur1YQhYdRpo7/sONtbTqX6JJsSHkZNlWcPcE+hPGRjFqRC8cRw478J55RgqT6DiVNQ8EtGGGUqh66SZM5t1lJMmflPxwnk5MetB5sCutDSYSxUYSDopnA7mEyiNvA7E01pVJ/MvnLAUusFh37tvuhXHQgW/WZ5V76xzI3EXlVQlbY/zSnTsWNd3MdiJdr8YEksey6jePAyd+6ugdX5Xd7xZ+YQw5QwJMxgiRpgbdhlGykuusmKw6YBOPj+pRmpPtOBb1NXMGqyoLbSuoT522W5KzljfR4p2Mo25bCr7hCQX5fQkHPepKGcM9JVlQujJqo1GwIcEzJdx0F0R4V0YUWMFPziU4BzJsi8zXxCKVEjhLxAKZ1ICLmcUio3jPiDQ5NIW8T0JyYhbiDaZuD4J1P4sDsBEY7im0wgDsujSYbfGtzUAkG6eADhTlNZIp1rPA9RIiOTPohFqs1RhIpRK5SI2uY/9Dg6XT8PxQcCTXGXg2mIACXcfec+YOLpYRRdkh9DX2k1ULsa2OuxvXBg7wNRHC3GnYssS4CEmUBE5hHXrBa/s7Eb9pXp2cRLlq7PiRLwwUTDQCWNHPDwi2B9H7M4tznENrGwRuLd7TCBe71leohqY8CwbPddy3Jqqs0uyTHVQT2QbQ7jFlK8NSJYosYYdQpg9tMpD+OuUet0f9rLp3meCaPKE8P6UNN0DgjiMAe9F5/Lk8eaT3xhNz2bsG4CzQZBz5+9tQ9flN9DZZB6MJSKlYNI76gwUpEk9R1AM6GRIlSOMYD1jcKoPlMpE1M+yIfqM4c6CNBjGcWhL1od3hQDyhXOzlrIIOEMmXgIMyil4zaMFGBKkrozG7UtjSDVZy0hZByA6YSQByCsZUrphy3as60AUmcCAabmLq5YApjwqdxNmKkSShVqL0cUi/SEQIwEn08YYSO6wn9SkjJqwj2hGTXhuT3fMvHYKOKoPgFg7CIT9y+5H+3vuB7xX1MYs1jDs8Pck/QvRhPaCvVaBG6T6whh9/mBLx6w2iVWA0kzCUOSWFyi/fH1+ayHvM/FNlKQIvVz+QaBJdmJJbyn5ohiA84GTHIRJkAmj+2/aiHmK4uUOfu+KV9o35sbAKTxtIB8oyNwcwKng04lns/Usp95bulzGPepiR9qCL6rJVj50ttY+sQi1M39G/61+F/YscOOqCutw7vL30V9oh4TO09Es5ACi25cB82mYb61GqqH8IzrsU9LEtP7GLX0m6YKYU06gqLnz37GRO1q6kkWrmwPmp9REw5U8Wb4uFw9AxqZCQgNNwYJSd5beYXBl3ORqAHAYS+4HyIo1MeYzzMbr7B7hOcZzjtUtg8ZKWD6R4/ipT4US9tyN5AUIhWvY9mGAehekd68oKUQxKidB2AurJRRYhhxCmDnlurU1gISgpzxdlmB6ij7njaSYITEpBj0VRM+6EEAQtIyamXh9oGsoLKfkkEkKmFUn8O+DrdoxTE45GUTi+p0GDH3wkmPm5gx4BLcAIsLEms2AuxiWFfrVlB81cHteN1yE/UFFF+t+Qq6LPxEgNGSisgSc/NGo9dM10bw+zauPUmuWDCEoPtyiu6/uAxaTcjgmirki3XMZnxV0sCwdYmqfwAY9B3FMxvCDUobibcqgRv4kwUfnTHPwLR/vIoGAM1nXorL3r0MlfFKvHLAKzhqwVEAgIWzFiIhSNTM+rW+7CoMFPJQESL4dSizaeQlQIbpjxOZCcKaXaSTmk17lyIMK6qTCDTq5VbEpzTqp2tBTlS5gFd9EsgD0uYTuao+TW4+NAYwarVr1NdkyIZRK+DeRbZ+jRSw+5vfYvc3vY5HxNiAeOVbmPPix3hm36czbzhPCArP8RCldAqAKyilE4R/f3gmDYBzGg1CSnMnRl0WMWlAKfZ6281RFm+y4jsFIVPxfiYQ1RZB8J9G/feIp9+ZL2XvNl/cSKUBOlM20aQEKN/gPmgEbUT2pdnPePtz+Z1J3HhjCoc+fSj0kJ5jDFXrqedkx0BS/rhzLQmeUBU1WjHM8lIvgAsPsiRNbA6e+XCOkzFPe1E+HWw8dQVwkrKDWVkDMON+v42eDKJHNWB9O166LoJ5gq6WeE/7JGob1jiqT9n4BB0sGdIxauKmGBQ6Ix2CJGU88kH/Shoo4kndp2o0BS9AQv1TtKUOXbxEjVDgwvtye9GgfjZGsvf6BKxvVccdADfF8ietz4ZRi6dh1GrWywdDi1omR5tCSsFbCmnNHimlFxFCphNCrrL/5T8D8FYK1WmUh6m5i6ujJC5T2jYo0O0Xq4JIErj2lhT+cdOW05sH2QeItnO+hMCSZ7IxDAXk6t+CJoBIPDFT9sos3gTcer17PUgtF4asyGzUgtB7GXDv3/z9IyBYGbASswktEQT+u9SsT+/dmQmSdlfZpsqycoRFveAFHM3TVM/FbkiEJ9p6wH0FColE+xXhOiPrM0tvpYLM85LBJ1HbsM49bPjWKkVhiATivJQrFKOWw6EgW1qRDW6/NoWz713va/OzUi8RJ9R/AFUxlMvb5NYnjboSyrBMayACJm9DzJtA/ulhmTFaOgWKOEY/2ywHMgQ65SnAr0XZuuqsOPvocSvEUDa5afOJtCSaEHIprEwEn9v/TrHLtiGE3YtJcsvdp5vW6Q4ANsblXn+bE5MDsgWIC0B871wCQYqQjWlBM0BkkdRtilTc6O17N0W8MiAco6ZLbNSyRTanxGwhbp65xH3ygLoezowJXtgls8rFu7MNzCwin/kzrdymFA9emvRsRiJU8b5kzmWqdnzPAjjtxmWeFEo8Xj5gnLT8iveuQJPPRq0+0JkgneQe8DJPfX/yXz/qOW+buUjUgjwiWwLdJGEARQZJM/10bYgk/RsA1Odhr2dzIh/0IkjKvCHulajlKiVkqs+PuhG80ys3gpOrRC2TLBgMOmnljBqAPQBMppTeQSm9A8BudtkfGuua1uHL4vT+FCO/pBj5ZfazXE+5BLPfD8H1/FYKrC7OuqmcsaUZtUKFRM20d0Yzz8Fowqi+w6IlGbWLDvS+uEigg5gNFWTqUgLL2DqpWbn1ZG2lQ64GzCrkU/UZSQJX35q9SCMX6R6hQNfl3ojsPPp+kfQdIMd8ZqLoyrt8qs9nvnsRywvWOfWKGJCG3gCZv0uQrdKWgi9nZMABXKQ7N92YCm0TnI3kemkN1zZ1PSRL87BOgtZEgyDZJhR4p3f2BLzJphdri4HfyrKuBkB2zih8mBaR1t4/Tv5hxrbZ3/m71UvUbJRzf+c4zL8PPP7N45slebJuujYX+74Z3OAb/Qg2FLR8n1QQiVgYZ4Ks25IMRZ8fKbZ78xlfeb2RzLx92VALBDySyl9YgVzsQQDghqnqpbywq/faqCXeD5XNPJYxvWyzTxgWM9P7J4rRGXp0tZR6qypPkjkAaL+KokO4BBpS5MSohbhHtNE6Zb6JnT+lSAg2mQ9++xw4oOpTAAAgAElEQVRWxi1DON9ahWVT2RwP/n6ZxFUEgMbols6a6IfIQAWZd4hx2TJrJ7N3X1sIPDuM6xyn+qwUpLWf9QzWKcvimAVJyTbGvX3VAHzcNftvxw52jRErUDCPxR2DnzXtfwyxHJlUUXX6Y7X/nuqCalRE3ZgAka2AUbsUwEd2cva7AXwA4JKW7Vbrx4aExNK3BVDQDLQNCIDKozFC0jIjzemjCmQNtgF9bWckEIl/PgVaMuZi5JcUNV8JuWMoRdvl1srORHzPD2PvH10bQR5Juhn1lWnw6sDwo9vvx9zbC5pnCd1iFi66N4WSEHZOYdrI1NZNxDHP5s+uM1fJcBAzmpaHCzGHVbaXokQtmlTn3GVllADv9VS/cKZMZz5tlXgsrMv+o4hzOUi6nQuTnalE/+ExmmNKAACDv6PO94pyzMbG4TV4ct/tA+t6eZB/fILm8ZKOAqNm5qaRYIyfZvqZ9XQM7MNjCDQAxbYJUDqJWjrJn8iIy9TxOtERIS7RafUSNUrp/QBGAXjE/rcDpfSBlu5YawalFB/8+sFmkagd91R4ytAYTb+JNEaBjVlueu/3CK6chRZhybx9NjotrPqUoXiT269MvhcvgbnI9q4SbRu+j7VgwLoMkE9JZVgEDWXCyI+xM8s1uqiO4Ip9c2PzeUbkWzF4XobIddkHSaHSha8IM4fVjJq34WiCC/cgcfzRKEA14L4J6rFPl3eTYX2BRT9ailFblAOjJkrUAhm1HOZ1uty5IijxPnPaoyZ62irvCOc9/hL5DRvN4NN8OkcPkVn5RJCeEUkYkkxQb2t6Cpv8ZhNpGUC73XMfsAY/nUQtXT9rBOl6c8T/gKEZiGhRz+8tiVBTh1K6nFI6n1L6GKX0l5bu1NaAt5e/ndOiDYvuy8NvC2EYNY1ap8Jnhma+6tLZWFx2lzUgyRaU2jGEPdny9iOZnIZlEcJFRk26IZZsXoNnwLX/yAeuna5hbYjgu4GqTz07g10RbB6lCGBKTt0f9wm/69dzAU5zieUF5H7eCJqHufYNUI99Q8K7w1lZDiz43sl2gjJJsJSerfl0OP5EHVfsr7eYjVoYac+6Qnm5mBREDEvywmD3hpaSqF2zl/8iJUCfhDdrKEsrFuE+ZVIHfmj+IuO2+cC89YLJzEbRRg25eYez+gqbrLy+PMLmFO5q50kX88J+L0j/0jFqIwSbcV4Vm7Kf1YnuZdS2AmeCbRBACEHVOorTHm15f/FMDL0bI+knqW5aBDgbZiqs6DuZoS1GNggrHSvjUnLl5PlHqW8DlG2IZnQzcKkCmhQ05KOhcXR99rGM6krq4Qz6g9KBNUaBsZ/lzrA6jJomby8T4sVLDxJGbvMz11AfQarPIK/ItUUKFaWY1kjBO3WfsYvnt24Ce75te30K9Xb4LoEJCykKNyAvknC2GQdJ1GS2QmERhp79pKpfICZX3uEdQH4jz0WLkgroo0zaZmqAachPYQaXgFy0+ZJBti/w9HC9wMRukDgT5MKorSqxOrC2GPitxHst3b4iSudFe14xW0Smkj8+ZAz7Rrqmw9Baj+pzy7a+FaPTb5tfcpIOjdGQjBrNklELuQBUBCmf7FvYzbKcC2eSC5HVTT9jJp7sACCla9IcsC0J8YTKQIuiiNf1yqiupB7OsUE6F+zhyJfUxGHUdLntViY2h0VN7s252mlmotZNkcwM0FWM2vpCazykjBrx7nSRJHDEghRW1J/rTWYr4MQn3FEV6+VtC/OhWmeM9qYAZ4JcQnek6+MPNcDVe+u4/Vr/xwvyl0hqXgYlFyY9iNGRXTMJYGrpxeVJI71tsux6Hy4v/bpCbzaFRsE8JqXlZqP2XS3B3/bW8HE34tMA1DYbABJ2+/6OimMu2pj5DnEZzNek5p13jGEujhQj2ooYtcChJ4RohJBFm6szWxOGLE/jqpIFcrWdaYyEUH2a1ok+DKP2ZXvv77AEW113/pjbsExXOefzkQujZqT8qk6ZRC2pb34htUqiFgvJUPxjD7fPYRl41VzQoKEhT559bPMyFZtEJt+TD96Zq3oxE0Yt0wORilmhRLWN+cNJDFhKMeUDilU3PISCxnCDFMT05iOsDqtedagAcjvIpRvnD7sTn3rPaTcNA8XPvWE55KIVn2w2gG9txyvZ4ZYSgCokajySOtIOXjqD/e+FvYeXUr3Xk+C+CVrO4Y3e6aOhKWqlQfyViyNRatqTXlG/aGLkk6gJz4X9Qp91BuYeoXvWXEoDduq4E64adxUiWwujRik1AXxCCOm8mfqz1aDjmvx6/H3dLvc4X41RkpaoMrVLGFfxN/t6OxS2f6qTYz4laqGdCbiNin/mp86Z7aBGCui00qqLGcPKbNRS+uZf0LftJn+XgVppqOc/4wyxxQ1POcwK1Schmu80HoS3+qhnBZtHKtVnJvMpW0btumkafqoCbt/FndSZhBAJUnfJoIrcbxJrDGQMlSbsVLNecDt4xiPhOtthtXp7y0v8Q3vjD5KaZeOAwg4ppgY8NEbdUY3Cb4zm9E1df1L30r1cwnOI43jPzhoa7NRKqjyppu7nbJNFfhurdN1Kp7ZM6l5bPB6v7dkZGwsIIon8xX7i+2vanLLq84jrzS9RI8LvcH343w4afmhDfIzaqUNPRfvi9ogQd+x1svlNWniE2XprAXxGCHmBEDKf/WvpjrVmUEpR0ZifFAEr+Kh0OQqcmkLYqDGEuU+8JSyjtjm8EDUz3GCVKJwJNkUz44p1E+hl5zn9qRpot5qiUhKhZYPEg6gl8U4vgiWd5G2WhfxgPGFL6v74STLIvjGhgE60jDz7/rmrhpUKfpK3UZO190G/cFLtpAbPtwor5WoygNcHaDhttuFZp5kE3MzU009lb0QDGDUjYCkMXBpunXQLcBHL53oOYpKNLBxQmBotqQEP7qT+sEESQ6LiEGDNvXylWCsXtox0DEUkBZi6/9STEiTWST19XelIQUojzhjdtLv8gN55VWbyGlEjwzCx80Shfrvzknd4dgjxSNQKGqnP0UsXJMpB8/WxUe5FdojiVbFJ3ZWeRbmxj4RQQbckwkzBvwCYCuBCAH/j/v1hQQhBJ+Tu8nn+ITrummR/ApK7xMmyUQtXSzbSu7AEe3Pk5AtrK7LrR+4i5iVgPxRltisYKXcj6bEcuO6WlDRp9Sflmzd5b9B3jA8YGK4O7rs2G+GStKs2L13LzLPPVEjLgPTOBG1n7IKXdx+cto2Pu/k3tjDg2/TaKYU/UWWqZlV9T1NTqz51UffTihEkUcsmmXo6j+el3S0X5kAJfMDwJfX8Mao/V3p/p9V+pABq+Bm1pHDITOSBUTM19f7D3r8g5RVl6b2CJfaqNnWie8J/UNaywE3/+fI+uH033SNpvfsa6wcZ38cpE1OyhZWosUNpknMuaoy6TFlcd93fiyIhXOFbEGHiqL0C4HsAEfvv9wCkz530OwdZn0MkTxtMnQGoiXAmaIwANevDbSJBC/cDRbw0PaSfnepknGu+OB7Z2JvxC54FUA2SeLw00OuWH4Y5TJd0+qcq9+/POgN/OSi3TTaIKJWdekWoOvi58Gs5cPwcHf+aFKzmYIzLijLgX+M5tSAxMpKomUS9EfKqT2l4AaIDWvrxWyMY1IeVcvH94lWYmXgPq+yi1G3KByMVIFG744qWPRzkU6K2uRk11vUgehF0tk3qmWcUkGHO8TrunuideJQAXRvVk9FIAaYR95UnBM9yZr8YhFSaV0hqcCoRaQqbkwVcJpbL99Ow9nI3nOq8Wf7TT9Bh7q7J7kVnzttFb/cmOOJU3VE3yg7+peUleGa4NZnEVytLqicZ3ycZHWiIuYxajGPUtrSNWtrWCSHHAJgNoBJAdwAdANwMYGLQc7930A1J5MpaBW1S2aAx6gZqvW+CBpMAh70o31WCFu7yCnm5AQ0IIUlMR3CbjdzjbO32fuacWsTDqFleTkldLQH8qcb1hPrHTeF2kXSea79UEHRcZdW5MU6wpiS3CRA0CiQEEwMIGQDsCOJrioNfhDFOG+NWjlnA2tQ0TUNC93qQMXwwuQ3+124V1hdaEknAIpzlKfkxJZVG9WloBswQBFSUEIaVcnlUwtxmnUn8xLVF8rFg+LwT8NwQDafMtyahSlpnalYGswHfb35v83zm6M3GRm1JB+CtvhqOeN6/UAs0a3zTHdzSqz6tG57fjmDSx+7NqrmXDvdN0PBbKXDqY1afV5b7K6EAogGDq2LUmmPMS9JCVNiKTCJJCRZCosaeEYfKtEt4c5Nfywn0QtceQIy7BjDbMf/AG8RAijOxoMybwy5aVwRsLCDQ7HLZAVmPx/FbiXW9Xvi4UeFljzlJx7CvKToUt8HKDSucPt2+w3l4omYT0NwWwJ8AAE0RgogesfvpMp8puhmCpgYgDCWfA2AMgPUAQCn9CkCbluxUawc1TRg9cgj6Y8NSZ1izkwbT81BI6u5p/4uOxGeo/dRw93cY1SehwF9nSE4+AtYLEouIJGwF4L5epnY7Mgz9NvPB4jcCpv4KUoOFUQGKEG28/NfdvylyZ9R5On/1Xhou288/uHOHnxtYh6wP6aQI7GRKCfB2H4L5Iy3PMJ3oyrn126Rh+LIjwS+V3nkoofEA3LEMYtTCSDtE5iCszZFK9RnhTjmf7d47sI51nMZEHiuL4I3+nERSsR8w6ftm1qwDyC+jRgO+l0pS2RQheHp7+UcrTrOFsRhzgYwc16cXB3nryzQsBcv6sqQjwZv9NNwwVcOFCqn57LY7BNZlpCggUX02xryEKZrwrg/5eg7ud9B102aEYrNPdss0r20f/3yqWrP75R30PpWWulLX/BJBb3vW/w6jJlkTejyOlOqjCvvUumKCF7fT8MP4/p49trioErP6z8KOHXf09EVmj0bp5j8g8QgzBZsopU4ITEKIgXzGWdgKQTQNkVsfyrkei/i6QxmGHsokYf/dkeDTrgQgxPmgSQ3YrnCyc8/jIwiWV8oXlgoEwCfdeUZNcZ8wiV/vL6+c7Zf5Ms7NFIyBXF0MfG8fNYIYtWwi/qeT1ojt5ToW/Mi/3VfDhz39Fe7ba9/AOmTf1WSMrAZ8184tXzikEs8OIc63NAmQ0gk2HTsDs0bNsU7LAbYp0rYVBwC2Qaps1AxiIBlCB94kOHiEZtT4ZyTzJFKtI3bCcZ4DkAim+lxdLJ8bZYJ9mYpRY6rPLYHNlaJM9il/rgQeGKf+YKYdDke5Zwt1S/OWctVvEvgi0eszCD9Vue0w2vHqQA1ddp4uvb9DvFJazmCkADPiT6fQJDJqgnZCNk/SfcOU5kodxXvZAX1AjzpPfTq3bvkx+qC7ZTdaIATOnlxn7UcmtTjy/+5IEN2uneP1ydBNL8bsQbMdeqGSqDnrWPj2VLGTEuINDU2i1scuibsLUzPlas6tQaL2CiHkzwAKCCGTAfwXwOMt263Wj6ieu7sub0itsj8RIXMPf2WAhosP9PYnqQN9CsY7v8XI0kHER7bQFwwhSu6cCg+sCgiyCWQesiBfYKrPsw/TnSTBQdK9MIzaw6MJHuU8idJJC33hL3LdBEM8H9G1wMklmwtM1Uco8M8/uYa7BRfPxe276Y5khPX/gtEX4Pjtjoeu6QG2KX4CGMR8JDlGTdZ9XdNDMmppb5HCq/r0X29/7p9RGIngrsk6Xusnf5FksbUZPDNMk66fKngnhMpsINfQPVsDZN/41GMNfNNePUlSjA4rpsEvxZZenknrrt5bMpAcwyE6wiQ14NMu1vXVxcpuALAYcSb94aW4MYnnJgAU7DTF7YKk/5EUQA2/kWNDgbeTi+q8YZmkjFoIiZrTB+H5lH0hYrhz1SSAJkjUTAJEuhZiY6EVJI1n1A7ofQDKopaqdGPCcn/971gd3R94yaep2T5WjZOGnORI7F4Z6H8hLR5HZWOVr1zWf7eYYDHnIU9iFhNcVhDBmlrr3TRKHYkaIYDZbLWxNUjU5gJYCWAhgGMBPAXgnJbs1NYAI4BRWxZ8UHLgcybIci5IN1rdG9VaZNQyUT/OmGfgtt10D5P40eFHeOrmke7kz9pOx9DlG0xakeK8pHJVfaY07yktnURNZGLCbsBi2hWGMFNG10jgSmd94lXlzGVep8DOnXd2ytlpk0l2RUZTI5qaUZMVEqIkrOzbmJrcplEnOhIhxo/ffOceHv6U4FEnyfZ33XD6rpzzMR0z5hl4dLS8o5XChwmKJba5JFtbqt1s6F9SZxus/9qMeQZWxYs8dZsyu00uSLXoCJPSgaVtCWLvPKkMg8PwaVfi2Lvyh4PBNX7PZL2QIjZ0QuD6/b4tAZV4G5rFrtnNjHkGvu7gPURn870otwz9EjVb9am7L2WpPt17Uhpw4FwDdU++jU2F1gbIp6I7Z9Q5KI1ZTDNj1FxwmyBclSpTfb7RX8OHguc2iRWgqqGt/bR3FFUSNY1oWFZNHPU0iVlMcMzQ0e3R97Gwjli5sDnJ/8ZvzkSqqab1S9TsoLd3A7gIVqiOu+mWZi9bAYIkahfM1HHcnPQbgqkBuumemFTr6+HRwStPtjATOkB5Rk24b4XEuNUH4SvzxqSUI3ihveDsJnkjcRWu2TMcB8NLs9KBhefgT4+BjFqICPspzlsKyDwNTjpGjRGVc44vwaX7+2+eqFfiwtEXpm8oSHJlEJx4nI7rp7n187Z2c7ab4/zNTpu8jRoPy24ssy6omBzGLCY1AMQvlTA0A7qWProu/00SRuBQeNDAVS092Bg6NJuEKr8jb5Mla1hYY6JEjR36yjcqnt8MkEpoWqCdbDy5k2kCTDNpjWMoL+EGzTKXGRKlr2wu60RPy0j+e5zmtMPPub167BX8oAIvDyQwo34LzmiZPy1cOolamLFVvR87lEU4htYkQNTg6AU3TptKLClUgRC+qDRqMWoNCa+hpc/22d5bNE4lKmphtFgcKe66Jx6pAoS3BweAmLv3asR6J0IlcfWoBrqFrb3S7oaEkD0AfAPgOgA3APiaEDIl+KnfP4IiFTdEgdWl7sc+d6aOk47z33/B4Dlov3Kk9YNAKR5ZVhVMoWVxq5I6QLlNjFDvZvKzQmoMuFIhcfPxeEcSTq8vehiFsIfg/5dhdUhvyJVlGTBqTKKmuXYPQYxaulAbgD/+0Hu9CJ4MsFlSGc7K8JeDNJx+tNVBszCGVaX+m6NEQ1ksFJUKxIoK4oknlOSIME8wo3akdBWjphM9QLWt6oRdrlGcMptTr2isTQNXzvqf7ylDM9CW1PnKRfCbb4LLl/nbyDZS5peB92STvRPRIw5RV35H7kAThtQXC8E8f6yxKi7fuOUMg6WMWg7mC38+TMeps/0ViIFL06H4/45Csy3lYX086TgvY5OwJcBjYmo1x8KDXQVRSie4bD/NCVHEDix1pXXo0uBOpLeG+FWSvKMEP+dkAXWJEYJuEQIa8bfTVFwuvZdBFYw6CBp1V6ePRtn/G9xcNjWgR00xfj3xGMSPmIpNcVcKtqnUMmoVzXQYnRIlag6jJkjU+D22bKO3MhIvcDMaUOCcw9x7PZkKYpwNuF0u05RomqU+9godiPN/ymzlEjVYwW0nUErHU0rHAZgA4JqW7VbrhxaQII5tMJftp+GavTR80Yng1wr/6hlaMwDElqgFraN0xs+iASxgx//hTpui6nOd30bVwaOjNDyxPcGCId4+d+F2rhS3GHxEQEGDog1eu7AgNWFYw+lMbHfarLP+T+puGIQgFXAY9bAp2E81xAmeGKF+UByqoG/7WRfNYfh1ovuMcwGAaAQ/b/jZU3b7ZA2Lz95duC+zTTCh8F4VJWqm4MWna7oy9Ium2IjZtzbax7FccihpHy1F3zad8Xknb7lOdFA9PTftYdR426GqUnzUQ8P5h8i5jk5xd2FJv5MR9Z/SBdB0uV+F58Q8hr9xMUVzSQieC7LxIgTUuYt/6BTDz5LvzEo+6pZ+8Xe+5TJ0OvIMFJ1/Ex4fQfCybce0Y69rnXuOGXgMdjv7epjbd0bXy25T1pUs8jI+H/bUsL7QS6sAoDzp9uvTod0C+5fOBKLzP28NvsEGlYTnoBGVn7SFbBg1/h5feA6bdvB7nkks5mb8iaeh61lXeu5vqmgHGZhEbUPCm9IlyWxX7Y4Tm6bw3pe9vCQOJFbgkaitLXZfml+Lkbj/wHnRQTreHl8OvV0dd42grslATUI29wjMFpEhh0eYbW4FpfRr7ve3AFa0UH+2GgSlHWEL5cOeGt7qGzDEQsJdFSEWT/OLOhNcx6mp2AmiV4UrErcCNXKMGgTiGtD/xhjBPZN0JARvuRjXP94O4I5pZfixmr/m4q6pfqLieEYFBr/0kovrp8rHcWSkp7IOlfFvcUE5vqkl+KkKuG/n9Ax3EGS2hZkwj6GzPWiG46nKgxANu3TZxVP27HANzdtvL94YvlMAUob8JRxGTWGjpgrPoVdoaG7rf4EBlUO5g6uij4q+GJoBhMit2sjN42bD/V6McC/uTKS6oZoiVyUm3fwMw6ED80fK+7h7ZX/nb34DWW0bL6f7KszpBQA6rkpzc0shS0atIe5/sLqg2olTdeckoRJ7gNbN2Clt3UXj9gQAjNp+AO6dqDvS4PKoyyScPPRkDO7eHv3vfRbxDj2UdZGYJE0Tk/pztJf3bieK+H2vTxmIzzrDN5f/b/v/w+CKcc7v2OCxyv54+iZJyp6MSMwAiEtnxfX3YzWwLECDAsBLtH1Sf+IrD6JbkRJ5IE6V6rOJSUWTjFGzBp13wvjfDt4GSbwASZJ+7bc95wz3GfsFllcRjLvsX544kzohiFOCMs4W1vmEVHM8VbcUlMuNELIPIWQfWHk+nyKEHE4ImQXL4/O9zdbDVgqNaMrJGlYaRPSIFcXSfiaWYOXeTUMkihceouP1Af5P98Ae/3X+TupAinCLnGbGQMigcZOVP818P7wG/3ckL3q2/icRijFH3uKrp3qD9X7iqXrWOa4KbzV3Qioc2w2vDZR3vmesk7QcsOJ7yXDogMPQFCU4bbaBLzukZ7iDwBvhssjjgc8R799hQ0UYmoGmKMEawbaYaARtCv0MEBGpbYb2TQlBNfNbV+vbiKrPIqJ5VBQ60aXq5F5vfQZE/RvMJTvc6HROefixvc1eGOwdrIgWCRXwtllUfTp95eqTSBzK953h/pB1jZPmLa8iuPgA/8fsWtQGF4+52P+sIIncEAe+6AC80887eA0ZJLgHwjsyZQJp+JYsaQm/4alio+3bOdiyZq0im8/gmsGekBE8ApNqG37bEcag8Woy/kCma/L0G/3OOAV/OcQ/Jw/tdygu3fEKkDhFpDq83lgmkE1JPEF1jtaL+8/pxxi+EDW3T/ZWrNGg8BwSiVrA9582xMrBGx9YDbOSQItaz5dELY+omf1moiJWgf5V1iGmSZCKs08Y56SJ4kGIxIuQsr+p35nNquC74SUomXYkV69VfuHoC9Gt3CsRJRprWCZ6JK2XUQMwzf4XB/ArgHEAxsPyAFXErv/jQIOaUQstvTC8C5oxalAYtKYDT6Qs1af7IEH6NCLpwKuuKG/oSVNOHxu7xz2Eoizmt6eIN9kn5yJg1mku0dqUcm0XbppyA2bMMzDz7EJ0vGW+sk80QKKi+j6G7hLZIKba1ICTjg0mqoTCH8cn5Mnzyw4k9IbHJFnv9hZOlvY3H1k7UlruFoRrhyEl7BBjn34bfZcs9qk++yCOjw/72LlP19QBb2XQCKCttoig+Zv3pK3ZUtUNtvritYEajjjV/R7F0WJQzf99tDjFQ2PdQLS86vPYYcc730sLWKdlk/ui+KBTnN8yuxYSiaB9kZt5Ot0BzeuZRzxlR/7JwLmHGXj6yP6YMc+d01MLdkQmyDYUSRD492LOLQu7u+P+mSRX91e1QMR+ucu5IMxj2o9xDhEP7PGA/0EAmoShZ0jowOyT/Wu+Z0VP3Lf7fejX3pLa6AWCTZM93j1K/B6YDVSS/sh+Z4+dKkf/NAWjFmQS06myEH0+XoIery9yypZW1wIA/jT4L9JnIpLQHklJmQ45o0aKrD6LdIgQvxu50pnAnqX84S+Iro3uXo2+Sxaj639fQ/83P0fvT5dYfdR0LJy1ECdsdwJePfBVPDDV+v6bxPexJV0FHEPaIChmiGEoA7C7uUMFWhlABDVCQAlRjAFpveE5KKVHBPw7UvXcHwWEkJzd1oke8UydmC12pTFvxWEZNSIwCBQBqs8swHt9JjhqkDJTACE44QQdm/5+mbP5EAA1BXJ7Bdj9UU1/x6BU0wPVzCKz+zN3hFAxDDwxDWTUSLgE3o6EnHuO4ahT5BUYfcvw+IjwjBoLi3HnZA1mJceA223dsPMNiCo2DwDhjBw4JBTqRleiZjcshDswiKE8EMi+oycWU4P3etQ+uPDqP/57lEZLpYx6jxdfRu3RRzu/eeblsMFHuxI1CZPHoAvzqilqecaaBqf+MiLoUdEDj+9lhZWUzSWaSEhP4+zULz5iCOocM55ZMuiWZtROmKPjxON03L2na+sgboDHz9Fx4cGchN3+/6l9nsIFoy9wnyMEpNhPAbSIYh7fdwdmn+T/Zs/t9xzum3IfAGBi37aI3XcXui94wXffgn0X4Pg+l/jK1zb7Pxyjlbz3JvEwavKBDmLUZNjxrkdRfcf12NDXr+59ep+npTHYNDs2XIIbCl6ixt6m6MDxqJlvOeGIdKa0foCv3lW2PeQGgSnqVGZpLaLcATefcf0aBbpF7DHk3536Dp4aUor162h0BOaKfRuZB6dOiMXgcZecFilp/eE5CCFdCSFXE0IeIYTMZ/82R+daMzSi5T5ZdQOwiTglbqwoK5ebC1Vaom/mHoMzOZUjvxE+sc+Tnk1U9PrMBvzETwkSNQD4rYyAFJV6CLsuSRnzwjBrAYoR5/uXu1IhZqegEz3wJEQF1dfl++v4zjZiVjHS/AYdxKiltHDBeR0jXLsufpw3FsgbKO9aZ3l1hZS+MtWNqRHUF3OeIACZvvcAACAASURBVPZ3iBtxdCjp4BSLG0amUe1TaZwJnECzguQtSKIm+46e1xeOszE7BY3JGfXzRtol0RJQIUxOQgf0ynZoU+4aKPLMXZRLyaMHbKrE8DOAKyqIl7OyVTZdyroAkB86aHMTEqbFcXpDKMjHV/xueiSzeC+iiisfYO/VrAObYgQrKohH4hoRXnxVKUETF9qGvXenkk6ezV4jGt447Wpfe7rEZgwAug8ZJl1P7YraoZCL4N9t+EjoNR1899UW16JA4kW5vtn/5dg4JnV3zntUn5LUTkDmjFplaSFqRk+SMg8dSzoiZvgJ0F5Tx2PdnuPwF44Z1jiJWolNpyt69IBeZUnsVgsCtITmHQdCgX9N0PDBwf3wWZ13jK+e8HdcN+E6VBe4zHk+Y+v5JWpW5TFhjD88bleQiH3o0XTHRq2b6V0jYdcWD0Ls5ySLmEJrvRI1Do8C+B7A9bA8QNm/PzQIcpeogZo+rh8AGuPeCara+LbbdwaWtpV3oq60zmsfKmHUzjpCx+Jd/OENbt/ldmlsLsJJBkxeosadNojAfIh82hcdXGlMShMianOeNRoLZEm0QIkaETbq9YXA+z1Z/fJneKlF0PIztcwCAzuMWsC8cNoLkaOSBz8GHqaLV3NwP/w2apm1l16iZlcrMGoakUfgl/YJXomaaEbEJMyNMT5kh3t/SbQEJhHsW+zGS+IuQyDOA3aPyp4JADTJBgnAO2Ei3rblErWk9DTurBGhD+JmQgLUgDKETTjPINo8SkGsPK7zjuAPhe7l9gn5WLlBZuXVakTD4QdOwbJ9dkXZaYc65Tr3znfseodbHmRnFhL8wfG3ycPR/m/zUN/ojaZ8ytBT0LHBYvQ007Wt4gOr6prc8zJTRo3BVJhAHT22qy/tVU1JDKMuvxlN/bpw7bpzkU0Borm0s97Pn3pAYNmlbtprN9+cLIuVYULnCfYv+/CUR4naRl0YS6b61L2d7rTfPlh+8dXQx/VGdOh4x0atlBL8d5prn02F/8NAt/ci2X68VUjUADRSSq+jlL5EKX2F/WvxnrVyEBJebRUM5kzgLo4GwatHxSzIcpJ5ahYmnZjA+rt2BCsOn+l7bkTtCOzdc29fOVN9ahGKBLfpJk2L0E3pOgUaNK+NhLDomw3ihMYQVZ+mh+FzJWpBIILqzZMmi1iJ6B8b6e2DrunYrctumNVvViADk7FEjbUrfK8PxrkeZy6jpuH4wcenrzwNKk/+s7R8fKfxnt+fTT8YuiLI8XY12/kLFWElnMwEmvw+g6gjysoYbn7jFPc4pvpsjsk/QkmkBFTiFQcAJVE1o8agBag+ZRI1ACDchkoEFZ3sJE+TCScGkyfJewhpLwDo0QB1tgSZqj7DSlrnj9KcmG4iDFUldrE/eo91QYMGXSOYdMnf0fboec51jaN/27dzvZezZYJ4DO5YjlV92iA+uivGXn8vyvY4DMeO64ZkbRQv7d8Rpw07DUcPPBo6tSR0bcwILt3xUgDAu7u6zKTMNhLInpkc0a0Sa3pVYcVArySwMGrgvb5unBN+Lzii/xHO3xok85U3GyEELwx2v9NORx0NUk6wap9JWFcKvG3bvk7vPh1dSrvglEHnSfu5ZOpkfFXrP4z+eeSfMb7j+BBv6keDKFEjcokaAcGEPfdAr1seBdE0pDja36eyj88Jz+9PRTz/89AI8dm8ufSqdTsTMFxLCDmfELIDIWQo+9fiPdsKoIqXFTYStVbpLkAKOHHLmgUvmL6ChwqDjFGr7+SqAHg+rRIRqQFsYVRDfTXx2SUAQEWsArVFtc5vdtrocO6JSHLJpNlGdPbIsy2JGleHKDhqjrgxzPhUTgCQou7Jlti2R+mIs4xRc1WRBHdN1vGvnYXNj+i4ctyVOHzA4Z7yX7t7fWRMEk6iRoQ/RCLW98ILfHHMiKbhhO1OSF+5UzUnUbP/rj12KmJDJzjlbKwenv4wqgq8/vj7nXMuer39OVZ1KYWIe3e/FyPbjfSVy8AkamxciMhYBDA/PD7uahNNYaxqC10v3ueGWI2srZHHWYnoEZ/qm317QzfwygBXfcWjJGGtL5nX5xdsnxRs3xynAd6GRfRWk5zGaaLZOY17DiUKiao43ztUl4JEKIy24URlb9g5RxsjVpLwdAjDqLGwCsKT7p9ppLWqNvh35YdDxZwG2qqGRFHMwI6PvoKudzzllPVqW4KBL32CEy56DkcMsJgfFih3Z1KF0R1GAwD2PPVU55kkkW/c2faxNB7B6Pmv44kZfmVV1/qBbrt8uBBec8F7oLFiTXPohk503LK7+/Ck0YPR5+3PseMl12PUu4uxzvayb1vUFo/v/TgmdJR73u591fU4+3DD980P6nMQrp94fah3FdF94q5Wt+PU816j21vjzjQg4tpIiUnpDOY4IT8hsHplamYtQPUJtOLwHBwGAjgGwGVw1Z5XtWSnthY8MkbzeGgxXDTmIjy/3/OBz5aP7AitpAK8oui23XR8Nv8iNAubxP/1O0Zah2h4DAAjnvsAfZcs9pWPMyoxIX6srzxqaEg+eBuO/JO/rlcPfBUPTX/I+f1DlcVYRrr1Q4qbOmM6jAFg2UlpRAv0MGyKcFkBBBs1r0TNqj/tCVVg1PgAtCqJJ2Nw09VtauGcCZBGosa38107+7Q4YEiIiuX4pso27u3lNQhmnp/lEk9bhh2feQdUcvm2Xb0BQVWfUPT6FGOchVV9XnKgjlnnlng9Lylw47gHnZ9PDyeYMc9AY6F/4zbsjBRUkHwxz2SNaPjHNCvPJutrtNbqe6/6UvtdrO+ye5dpYG/M5o4oUWPEnQRwNrI4iDSRcCTO/KA6AaMF5k5c09UVpeizcAmij7ytbJfh2ukaPraDxX6cJmjsq/3ZpuViSQfgiqt28907tdtULJy1UFmXckjS6J74jZdnOvQM1b0tAWb/RFLu4ZFPoZRUBEDVMvXaETCok7U4ozUuzUhxE2dZLy7bDFdeE/HH6yOa7oxxptLIILOAfOPog6ag75LF+L7OFgrYNL1PZR8snLUQw9sNB+BnglMi/bbtag2FHjnI1plInAkc0K0j4O3eALpRSsdRSifY/3Zu6Y5tTXj0eL/6qW1RW/xvuj/tjQPKCL/90zkEUDTp3o1Jj8ntIdKqPoXfiSL/Dk1BUSRJ/Ou0wW0co++0PJRiw3dGkpv0F+94seOhpBHNM6VNYSNqMuBRffLw2AHYtmfpJDSE+Bk1TRhT3ztp8hOaL3AtgSctDI/69u43YndQYgX09LvCE+em1/sTnDE7ipKZp8s7FwLTbv03Kv95DQr3mOUpP3346Xhi7yekcdV4JGJy/VibAvc5FZ1mnqWmQqJGQPzjTrwnZYbOJd64DtQUJLD2/Q6jYyN2z23o9qR1EBIlaka5hMEnBHfPHYquj79m99FCgRbBY3s+hnnb+9U8ou2jFMI9MkZNL69w+v8zH+OMGwtmAwVINlRbtRu0yTBsKLCcQOYcr+P66cGknYWd+KWSt2sEiiJ+6Vm6PIdKhxjGMPh1nwDUzIOoUt4SqC+pAQAYVa6UPcI52ER0uZRXkyV9zwAzR3ZG7M5/ouv8F50yh1HTKCbf5XqzsvU0sHog+sQ4UxXiDLCrZs6QUQsKXdNSWBOz1oFR7aVfTKtTEvF6RDjLzZ5fjaUxz2827doVtbN/h5jHMq9PEJgqI8LNhDBf7xMA6iN6FiCEnEIIWUQI+YwQcqpdVkkIeY4Q8pX9f4VdTggh1xFCviaEfNoa1a6RPiOk5XVlfkN9F/JJQylFo49Rk1uCpmPUDN5zj1IkSvy6EEopiowARo1ro6q8GDWjJwEAeNPKmB5DxxIryCEBgUdyIMzv30rdTb454lUT8m05yZQlBGZTLXfiFggjJcRh1JRx1FSMmvBNZLZNz21HUHT64Vhd7BIN1syhVUNQV1rn43J0ojuJ7wgFfq7JnJjzTE55cQxtx/olHxEtYrWfDn+7C6+N94cDuG/3+3DW9mf52uPBGGeHUROYFRkx7Pbw3dK6bp58MxL8BKHyDUKss9uIMdCrLVWkyakfG46biW73WxJg9m0jWgTXjL8G5xx8C7TiMqdGwHrHbuXdEOWkZ8wYnwiHIzFMQtHBE6C38QZb5hk1oxTQZ+2OijOvcQ4gV+6rI2GrZ4ps40dCCB6Z/ohbhyAlILYaMGjfXNSZ4NrpGj6x1ckrywkSBkFJgP3zmiIrvtnf9vbOxR7FfntFmccb3x0agomUQTXHSCSG+muuRsVFf/Jde2T6I8r4a/nEIZdeBsyaiprL73HK+FyXXaLDpM/lKlEjhKDbDjtCq3CZFRazMlKmIyah4V3Lunqcu1zVp+6snYwZtTw6C4TFyGvvhjFrD5SdcrmnfO6Iubhq3FUYWDPQ+wA71dn/Ra7/D+InHoAVxd797N+7/xs3T7o5bfsmIT4JNwCAaluFRK0tgCWEkGfzEZ6DEDIAlip1BIDBAKYSQnoCmAvgBUppTwAv2L8BYAqAnva/2QBuyrbtloKKiAap1qjJggh6J4aMUTM4mw2esPLSpnun3Otr48QJPdyYW5QiUVLtu4eCojiqyLUENTPI26jx8NioEb9E7ecqglen9wMZ0Rmv9fcydcf2Pdf5my0M2Rg+W8cxxrLYXPaaUobnIK5HqafvokRN8oqrSwg6H3OWV8JhP9dFkfiZEIKf5l6A1C79PGELAOCIrv7wBMv2noyKM2f5ys/b4Tzctdtd0jYyweDhQ/H+9of5ymuLazGqdhQAoLwgghW77YB2l/g3yzOGn4GeG2xJg8Q71LNnGBSxfpZKlh+z7dttj+qCarQrjeOjQVYaMCowavv32h8AAj2u+Dhqw049G0bXfgC8MZMm1U2Sz3HnMOC2ef84HWtGtEXZ8X/x3HrVuKtwzEDXBKH9kf5x4RM6E42g17y/gUSijkRtYwHBV138ErJ2Re3Qsbijp99OPdE431UpNsaBN/pr/gMCN5+N2qhH5U0JwQc9NXRss4O3vZAbOs88p/ElUEJFH0k0jhFTpqDd/rN913pW9ET/6v6Sp/KL2opC9J13JcfcW2YiPxx1KAoPnYzVTf5nrh5/dV4cHkQ400oYUMqp+VNU8j00zVk7mTo5bAmJWrfaCvScd5XP7KAwUohdu+zqu99ZQ/ar9x/YB11PvMA3TjWFNRjTYQzSSaVFybD7sxUHvOVwPiz15yXIT3iOvgDeppQ2UEqTAF6x698TADt63w2AWeTvCeAeauFtAOWEkFqx0i0J1edXLVqtiKLq5Hn2s7bXJywR78S6iT5GTYu7ErX3OVdtXi25XRv/SbgkHsGrXe1I3BSIcJK5g/scbBVT6olBFPYdmhXUWfT6TJneCb6inCBeU4I+9zyLlO5lU/nguKkAidpGPlGx5OjnSNTS2Kj5F663r0Gpc/hLjp+ASkIAgkkHH4ROV97ha6Z9vLfv/kmXXod2R831le/fa38Mays/yWcKVZ48xxaLAOP+fgcq9vFvlrP6z0LMtCU9EhWh0kZNMj6EECwcspfzIH/L9O7TASBQ7aDy+mTfWEZgnQwbGrPfcRutLwAKr/o7SIH3VN6ppBNOHnqy2++Yf83wErW2Z5zk/M0zmm3sCKqqMfKp+g0mUVOstxLgoR39E71jcUcUcvlye770CVJcyBG2Rmd09qp9w0rHPKaF3I+CnfwezgTAmcPPdJ9Np46T5LJsLdj1zD+j7uzr8ON6P6c2uW4yGlONeW/TsQcWPg0zcCcgOHJMVyTbRVF+2CTnRqLpKDKK0LeyL/66418zalMW/7LVIk88lMpGjWIrCM/Bh+TIU3iORQB2IoRUEUIKAewOoBOAtpTS5XabywEw2W8HAD9yz/9kl3lACJlNCHmfEPL+ypUrc+he5hjXO9gmSETvD5YgNmIyAKDDTpYq8ZWBBAv2W4Dqgmo0CUEZeTUMz3yE8TByiCiliHLSD94DptBQM2oqJB3iIUgEQT2MWofyAoAze1nPvVpUiwrMjft3KkCi1sRJR6hkCqty1jGovIh8XnuS8WV1fjtgAgB4g0MSgr17+MOaBG1MKaHNkvG9pH3et+e+0vKskaNuw7TfxRfGggLLquUDL6a5Ykg5GzOBxm0QTiiQICKpyxk1NtbB3lpWW/ymZGrydaWSdHm6YjdVOrAKJfu5oVeYV/QZw89A3FnACsZLbMcO/qraN3u/t1gaS/HpfZ8WfeI8TUqTzFOgS2UxSMyEyUvfuN1rUM0gSS+syiom9kKXWx/3XT2m42Qc1t+V4LLxVUk4VKFRWhN2GuJdp9FO1nxoW9jWU56PdcvUmuK85NWaPdoUY+DLn6D2z9e79FfXoWs6Hpz2IHbunJlZ+RYQqGUMZw7nqa+myuuTbgXhOQgh9YSQ9fa/RkJIihCyPtsGKaWLAVwO4DkAz8CygUsGPCL7DL7hpJTeSikdTikdXlNTk233ssKwugrMv/UC6bV3Dn4n8NnZs/bCjHmGJ8l6IuLdBHjj2rCR7J37XVN39G9vifH1OHWIJKXUo97UYvLjiRhrK+m4FnnvM6np+TgVRVH0evtz53d9oUugPzj0A6c83qXAsxmVxS014qj2o3x9qerP5euTMByig4an35ortfDZA/lv94ERh+MuuRAz5hn4rh2XH45o2LPHnphR9R9vvQHSQZOTOPZdshgdb37Md8/CWQsxo/cMX3kuGFZnqS5jnb2HAuYxOqKd3O6SgUk8xfAoIMDaYoJ5x/lD1PSv6o/bd7kdgFfSZRp8tHr3ficbQwCRNHW54Tl7Vm5A7C3j21TFXBMlXUSS2ompPokQLJcxmtY6syXoVdb8Luzf09PPPpV9vO0wiVoWu9GKNuqUzA6/yA3F4s4EbUsL0OeTL/DmlZbd3Fe1QL8qS528cNZC3DLpFgDAkGqX6c406wVDS6gJNxcOGNcfN517n/O7+3MfAbDU2Av2XQDAYtr4lFnZIknUtFYKzkbNWxz8oXh6uCVUn5lDPn9WtLGY5TVdvKYoA6otL3nRiYnBciZw39sdgi0fniPt0YVS6nG1IITsBcu+LGtQSm8HcLtd3yWwpGS/EkJqKaXLbdXmCvv2n2BJ3Bg6Avg5l/ZbAirpVjqDfxmaBFUkiaYJKx0Ayv0xoU8bfHvfnejcuT3w/f12sXXHgn0XYG3fr9G9i98YfcG+C1AWK/OUsYC34msnzaSPcPMbYYNEqzHneB3PH/kC1q11b2xT3BZP7P0EOhT7U8Gcduz++PbW80CbNKmogW2YfD9id/0Tl3z6Vywyf8QNNkGK6BGc0P02AIf7O6VATJJb0jnYKfI3ihI1nnkok4Se4CF6OuULx4/rjqV33Iy6/t4QHzWFNXhy7ydRWxxsXeDE+kt6z1gsfIeYMYBBtk6SnCqb3yDYeAVK1BTSl8B0MdS5ydcnk8g3NJ9kV+KZyBJHG228tqCV9qGD/Q8AA8aOQMPsk1G9wwTPveM7jkeH6HAAB1l9C2GjxlASKUF9ot75XfT3h4Dpk9wbOKZsfSErcgvvH6dhqu2BOnNUF0w5QceGAuA9TkpcHC3GU/s8hWRzKRphmSqrsiw460KhmtqaGTUAvqwcTnmemZxUGnmKrz1CIBMN6UTHkaeYeGC837D+pRkvOWvXundrYNRsCFqJfjOn4dQ2izB21GhP+f699sfwdsPRrUwel7TP6XMRX/G9r7z5t/E4b0Z+TE6yRcYrhVL6KICcwnMQQtrY/3cGsA+A+wHMB8AsqGcBYKKF+QAOs70/RwFYx1SkrQmqE0g2xCghMmY52GywwI3Mlqjb8FEw2nR2ApeyDai2uBZ9R4yF0cZ/2qgtrvXZsTFnAvH1UjTlY9Q8hEQyTivLCbSSCu/2qBuoK62TMrpRQ0OyxC4XTo1RLepMal69023UjqhvX4qNBcRTJ0lxyaXtBa8PrEH7e67ztQsAh1YM9hcKNmqZOJdMG1SL1aefiLp7/+G79s9d/olH9nzEV54PaBpB19HjoJX5vcg6l3b2EG0ZnHmVSHjK2XOUvatik+YZhATnUcmPXRiJmiwpO/+sDKIDDw9TkzNqPpWkRJL7QQ8CMmsP1Fx2j6f88AGH49Kxl2K3Lq6nrqFr6LjTrr5QFJqmoVNxV7edQjt9Edeliw+Q05T/TPNKcqsqvc76ps1YxIbV4uVBTKLuXv/L2IsdqYOmaVhVZuXsFBmBTiWdUMjRJCa1F8dNJf13IsRvTcyABBEFo8YgS6ieDVznLGF8mTOBsI0795veAw4hBBsKCeKde/raqC6o9hzGtwaJGlXsrTFDx89V/jzKhBAlkwYA7SdMReUBJ/rKzaYOebMNzhZpxT2EkH24nxqA4cjdfO9hQkgVgASAOZTSNYSQywA8SAg5CsAPAPa3730Klh3b1wAaAByRY9stAqLgebNJKdIseKiRWAF+Ou0UaF88DeBbz7VbJ9+KXzb+oqxr0gWXwTzvMLS54hZP+exBs9GcasZ+vfbLuH8AkFCoPmWMGgD8cMwsxNZ8AstE0cW1E65Fc6rZqorn59LYUKmMngkhShs1Rth4Rm1tg8tosA28zZhRKBw2HvDHDUaZJKmz04xqYxJUnzyTQgjBmGPmSJ9jHpitEU2aXKLmJN1WRG6XwYwqJGpaejszKsm2YdWT/oAkYxRMkgMDQQj6zPPHAo9oEUztNtW6RcW4skMC0b3roNCiBTwTtKxK3j8+i4jdHQ/Wnn0t2j3wN3S99VHQf1kBl/nu8BlV0oWZMDhJtrPeFRI1FUTG7qdTTkT3Hz7w3XfL5FuwsmHz2h2Hwdm798XiFwZh0H5eGtq2sC2OH3w89ui2R17aYRI18Xsyz3if7Rr7nfIyapkEv92ahZ3ZmAm0ZD35QBi93DTu7ySsBO175tIopXSspGwVgImScgpAvpO1IigNY7Mg+omYa/+iV+sgkSgmzz4Ory8bADxvGSmP6zgOALBD+x2kdTAM7NYOuG+Br7woUoSzRpyVcd8csM0zjY0aw66nz8Uby94Anj/OU84buWZzihMdAAiIG55DEVCXZ54PGtEJazrG0WanUVj7xvt2RzQYmoHBNYOxX4+ZeHPAGRi9yHqWZyDHdhiL15a9xqnSrGszR9VhbfsYnhoUAdDobHo60dG/qr+TpmZrRjPzqmz2StRYQNwx23UAKgjaHHmw53r/qv7oXNIZpw510/GkdAWjhvSMmqaQagQFSiaCBJRHSiFRY/h63HD0+cYfpf+kISfhm7XfKJ9zoYifyBmG8+1rxeW+rqq8mf02l973GLfLBGAXr6pVFXUgHd0yuHHPNo6aiMnHy8k8SyXU2lBRFMXom//jKyeEZJQeLh2cg53wTXivT28H7OdS3kMUY9DC7Emth0VRY4/DDgJ557+oOe0UT/nEuom4fdHtOKTfIVuoZ/lHGBu1rX9X2QzIpxg/GbNP0QZFr9ddCRTbBIe3HY4bJt6Qt/aygZa0Nmif6tNMccYp8mfzMlZMoCcyagEBbxlh4zfxuqoi1D1vGQL/sIudqkTTQAjBfbtbxsLTDvkH6h/8Brt+RD3OCzdOuhEHP3kwgI9Z426dL36M8x7dE1j3rWu7RggemNrywTo3B5qZJEshUautjKHvW5+Lj6EwUogn93nSU6YbvBEzV25/pyAbNWVg3kBJtnzjA+w5EzA9p93ij1cIWBLqjBBgKqFpnDY9XmiXSyRYviq9F6qKo6ivJDDq/YxueawctUW1ymjt6aQJfJR+FpzaZ5vJhjkNc7oNwSCmM5Ae8HHUPOXsxlwkaluB6nPiiL7Ae361R3VBNRbs5xdObM1QMmqEEH9eFReUUnpRC/Rnq0VlrF36m0KiOW4xauL+xDZBpirckujV3TLyj/fxuqO3K2qnDIuRDuloQ2MEiHsFONJNQOX16TBqqkCbzh+S2GzOJe81k5ruhqRwn29NIvR8gak+adI7SdkcTZgJ3zMqMA/UaPuoZ6xYMnBVWA8gO9vQIFW1ykYt71ClTwKBRghE1pTvUVgvy6KYgf5v+pllAHjtQCud1n1vL5VeT7eZ81H6XWcC7z1fto+jxw8NSNV6HYLGdBiDJ799EnFdnhpvG0QoVJyKrANOOkIh9RqTUIeZ3xGdgEQoaOL3R7tCoxW9epBEbaOkrAjAUQCqAGxj1Di0L1QbKWaKZIFt1ClQZIdRM7c8o3b6gePxc90N6DTMa0fVu7I3eq/fH4BfcpTuBJ1O9Xn8HB0vTPy3XRejRmrVp4pRU54WFSoxCupGnQ9g1FTGvq1pwecLro2aglFLhWfUjtqxK76782Z06dsfG7jhLYuVWR6oRWoPVFV8sUCJGg2QqLUwo6aqmV8bGoGfUeNVn3nsXibBiXnwEjWV08CXB47AgkGv4cxB3qx/F46+EHMGzwkMtL0NLoipNjORP8AkaqZQHH7ixAwdhQ8/jkrqZwNeOeCV0PVsQ36gZNQopU72AUJICYBTYBnyP4DcMhNsQxpECuUhGdgJtDVIaCK6hrodfSaFAICYGZwaVm3PF+ylsrGAoKinN+Am4XKwVV8xF2TDTT7V50PTrPyP6SVqalsQR2omeBma1FRK4n7PErXGqLXJirS/wLCcLTJRa1n5DS2bS63JKwXoXCqPeeQ+Ky8P5W0ti2uXizNBGKRh6q254m9fDCGypSEdI6EsGjXwcxXxzf+oHkWnUm+e1G1QgwQcLAC1RA2CjVoYL2oenXv5vUMBb5iZbdg8CKRmdqL0iwF8CoupG0opPYtSuiLouT8i8kk7L953ENbt1B+dbrrEU961rCtmD5qNv41v3Xyy6Y+JHgoZMTTsVk6iVjN9liVRExi13pVWmiZm66TyaHMlY95ySjlzaVGihvQStd8jo3bguecgsX0d2l1zu6f8oD4HYWbfmZjV35+rNAwyzVyTLnm89JmAZzeX6lOZkJwQJCUps7wpm/LYkTzkMDQd1ae3Y844/v6m/2aF5qg+veUqZwIm4aTCPJJ5nW+DGq1pRMKr9gAAF6RJREFU2ioZNULIlQDeA1APYCCl9AJK6ZrN1rOtDGEO4cu264JIX3+08AN6H4BD+x3q/K4ujmHUrQ+heII3HREhBCcNOQmdSlr3adRUDEa6xLaZbNLU94cFAqK0UXMYJ+XHsq8Lm3yQ6pNSiv+N1mAWURRNP9xz7eyRZ6NrWVe0L24f/DJbIfp2qsage59BpPtAT3mBUYCzRpyFoog/cn8YZOr5m5WNWoCEItPMH5ni672OhlZEUTjlIE/5+Tucj+5l3VFVUIVEUmJ36ekj8OPQ7oj0KvPdd0jfQ5w8vmGQjy1b5fW5jSHIE6j8BOnm5fWWfzX9KGjFFIW7eLOZXDjmQvQo7+FkH9mGrQdBNmqnA2gCcA6As7nJQGA5E5SqHvyjwNAMDKqW5b6TY9IDT0vLzxl1Tr661CrgBsBUQOm1lk1rgvSBqJOyy8JzeB4NkIw5qk+JjdoPbQgKXngKRrnXTnF0h9GY32F+uNfYBgCZz4FMggszLO47BqOXPoOCsW4A2p97VKP9178BsBxiGMZ3HI+Xf3o5s04F4ICT5wAn+8NQjO04FmM7WlGLmlMpH2HWBNXnLv9+Qlr/3BFzM+pPTgI1QgFKlIFHtyE/0BmNE06yKpvbGX86GfjTyb56duq4E3bquFPLdPJ3iNbk+Rpko7Zt9aXBR4d+tKW70CqRyppwZ6L6tJlBiUTtq/YEI76kWFHmrW9U7Sg89s1jSiPm7ypqMWDZt4h07+d9rv0oEPqj9UOQtqV1UNiGjJCp2lElhQ2SqB3192sAXOMpm/iE5QUpRki7fuL1GfUnH6gsiqFRKOOnV0ksf2fkdFLuQBAAtHXYzP2eoTmaAG+5KjPBNvz+sO0L5wmlBcEpd/5IyDYAZqb2SYA8jtr8UQSRf1yI79t5Kzx/h/Px5N5P+vKWMky847+ouvVqFOzsjTR+zshz0HejHUpAlzsMZJOBYhv8yHQObA2pbjJF1+oiRP/zALotcKWxPAP76PSH8tZWTgI1pw57Tfg4CXbf7+8bbU64Tk5y2rO150zdhvTIPGP4NkixfZdKvDHvdAyoa+O7dueud6JNob/89wozS6YlE6mUm8HKu9Vo0EAJQeWYicB/LvRci+iRQC/CytJCYKcpvvKIHkGEWu9EDC9DznJbbpOo5QeGrqH+8r+iLuk3h31w6oM+u6ff67h3H+zNKcu/ZmlB/rzu9GxORwwsQo6zFhUOEtsYtZyg02Bngm1oGbSmWbuNUcsjxsw6Wlo+vN3wzdyTLQuVV1o64+LMFoZ1d6eKAry7z64YWGclV2cbN6UU5+9wPjqXBId3CIvkuTdA++d5KJl5uqf8ugnX4dFvHkXH4o55aWcbgBF77iMt71vV11eWC5+xNcGzSSsS0WeDGcM74a0pYzBo1Ha+a2cOPxND2w6VPMU6Zf+nyl+6zZkgT5A7v2yTqP1xsI1R24a8w1F9qpwGFBcyUWM56TVBMfmSv0uu06wTzsuw49iRwNhnfeWdSjvhpCEn5a2dbcgMewysxY+dC1HTv4fv2rC2wzCt2zTJU1sfPGtGy9/GHI/omHDNbdJrh/U/LPDZz3afgoGvL0ATkzLb6/fcUediwf+3d/9BdpX1Hcff3yQEEhDCj2AhICGCWIoCISCktGJg+CUlWChStKBgNZX6A/wBlmmlP3SK0OJYOjJUBO0oP4ygwFQFEaUzSmrAAEGIpAZDECWOGBCo/Pr2j/Pc5OzmbnY37N5zsvt+zezsuc859+6zz5y997PPc57z/GzdEj5jtdezV+ac9i4mLLmd6Wd/pE/5/FfPZ+GyhZywxwkN1Uy9YlDTiNvYyQTDej/vch+1qtgPhfFkx623YMdb7uq676qjr+ptZUZRveew/8zjppz4qWpCxrK3HNGn/OS9TubkvU7mrNu6L7Ku4Tn2sAPg7gfXK995q5257eTbGqjR+NCm/y/a8RevMeWlHoSlFdtVywptNvM1fcrn7jwXwHUENaa0uVcq1tuojOUbPku9ZI+aRtxgsz4HHPocxgVHb7zyel5c8j22OLTvxf8XzL2ABfsuYKvJWw35taS22ySizgZWW5C08QxqGnG5kR21w3k7336AGZqTJ04edH1IaVNj1pF6q009wQ59asRt7KRxP4yk7uyVksYvg5pG3EAn1eBrffphJI0V3p5DGhkGNY24tW/PA67pOdCNMSVtagZa5N6gpk1Zm/oNDGpqjxb9YUgampXbzwRg899/XZ/yfadXqyvUF7mXNHxOJlBrOPQpbXpOvfQynvnBN9l6Xt+bC7/n9e/hqN2OYta0WQ3VTNp4bfo0Mqhp5OWL3YtHdAkpSW2wzZTN2Gbe+itATIgJhjRpBBjU1HNtmvYsbSpWLngXr/nVsvXKL513KU8+92QDNZLUCwY1jbgzT5pH3Hwh0886o0/57FfOZsepO7Jg3wUN1UzadB31wQ91LX/jrm/scU2kcaBF/QkGNY24Q//gVfDDB9Yr33ry1tz2Z65NJ0nSUDnrU5IkqaUMapIkSTVtupbaoCZJktRSBjVJkqSWcjKBWmObKZux5PW7sttzT62378Q9T2TKpCkN1EqSNN606f7rBjW1xqSJEzj8ulu67rtg7gW9rYwkSS3g0KckSVJNizrUDGqSJEltZVCTJElqKYOaJElSTbRoNoFBTZIkqaUMapIkSS1lUJMkSapp0cinQU2SJKmtDGqSJEktZVCTJEmqadHIp0FNkiSprQxqkiRJLWVQkyRJqnHWpyRJkgZlUJMkSeqjPV1qBjVJkqSWMqhJkiS1lEFNkiSpxskEkiRJGpRBTZIkqaUaCWoRcXZE3B8RSyPi6ojYIiKuiogVEbGkfO1Xjo2I+ExELI+IeyNidhN1liRJ40OLRj6Z1OsfGBEzgPcDe2fmsxFxHXBK2f2RzFzY7ynHAHuWrzcAny3fJUmSxrSmhj4nAVMiYhIwFfj5Bo6dD3wxK3cC0yJip15UUpIkqUk9D2qZ+ShwMbASeAxYk5m3lN2fKMObl0TE5qVsBvBI7SVWlbI+IuLdEbE4IhavXr16FH8DSZI0lkWZ9tmG2Z89D2oRsS1VL9nuwM7AlhHxduBjwGuBA4HtgHM7T+nyMrleQeblmTknM+dMnz59VOouSZLGjxbktEaGPo8AVmTm6sx8HrgemJuZj5Xhzd8BVwIHleNXAbvWnr8LGx4qlSRJ2midgBYt6FJrIqitBA6OiKlRtcDhwAOd685K2QnA0nL8jcBpZfbnwVRDpY81UG9JkjSOTGg+p/V+1mdmLoqIhcDdwAvAj4DLgW9ExHSqILsEWFCe8l/AscBy4Bngnb2usyRJGn+iBYOfPQ9qAJn5ceDj/YrnDXBsAmeNeqUkSZKoTSJoPqe5MoEkSVI3bRj6NKhJkiR10YahT4OaJElSTSegtWDSp0FNkiSpmwktSGoGNUmSpC6aj2kGNUmSpD6c9SlJktRyDn1KkiS1VAtymkFNkiSpG3vUJEmSWqr5mGZQkyRJ6qPTkdaCDjWDmiRJUjfRgqRmUJMkSeqi+ZhmUJMkSerDJaQkSZJazlmfkiRJLdV8TDOoSZIk9bFu1mfzUc2gJkmS1EULcppBTZIkqRuDmiRJUsusHfpswVVqBjVJkqQu7FGTJElqmU5PmrfnkCRJaqnmY5pBTZIkqbsWJDWDmiRJUk1nxNOhT0mSpJbJrL43H9MMapIkSX0kVVJrQYeaQU2SJKmu06Pm0KckSVLLvJSdHjWDmiRJUqt4jZokSVLLtaBDzaAmSZJU1xn69Bo1SZKkllk79Nl8TjOoSZIk1ZWc5jVqkiRJbfNSi7rUDGqSJEk16+6j1mw9wKAmSZLUR3buo9ZwPcCgJkmS1Mfaa9Qc+pQkSWoXhz4lSZJaau0SUi0Y/DSoSZIk1WSL7s9hUJMkSapJOisTNFwRDGqSJEl9rFuUvfmkZlCTJEmqadH9bg1qkiRJdeuGPptPagY1SZKkLia04CK1SU1XQJIkqU0OmbU9px2yG+89bI+mq2JQkyRJqps0cQL/MH+fpqsBOPQpSZLUWgY1SZKkljKoSZIktVQjQS0izo6I+yNiaURcHRFbRMTuEbEoIh6KiGsjYnI5dvPyeHnZP7OJOkuSJPVaz4NaRMwA3g/Mycx9gInAKcCFwCWZuSfwBHBmecqZwBOZuQdwSTlOkiRpzGtq6HMSMCUiJgFTgceAecDCsv8LwAlle355TNl/eEQL7kAnSZI0ynoe1DLzUeBiYCVVQFsD3AX8JjNfKIetAmaU7RnAI+W5L5Tjt+//uhHx7ohYHBGLV69ePbq/hCRJUg80MfS5LVUv2e7AzsCWwDFdDs3OUzawb11B5uWZOScz50yfPn2kqitJktSYJoY+jwBWZObqzHweuB6YC0wrQ6EAuwA/L9urgF0Byv5tgF/3tsqSJEm910RQWwkcHBFTy7VmhwM/Bm4HTirHnA58vWzfWB5T9n8nM9frUZMkSRprmrhGbRHVpIC7gftKHS4HzgXOiYjlVNegXVGecgWwfSk/Bziv13WWJElqQozFzqk5c+bk4sWLm66GJEnSoCLirsyc022fKxNIkiS11JjsUYuI1cDPevCjdgB+1YOfs6mznQZnGw2N7TQ0ttPgbKOhsZ2G5uW2026Z2fWWFWMyqPVKRCweqKtS69hOg7ONhsZ2GhrbaXC20dDYTkMzmu3k0KckSVJLGdQkSZJayqD28lzedAU2EbbT4GyjobGdhsZ2GpxtNDS209CMWjt5jZokSVJL2aMmSZLUUga1jRARR0fEsohYHhHjeqWEiNg1Im6PiAci4v6I+EAp3y4ibo2Ih8r3bUt5RMRnStvdGxGzm/0NeiciJkbEjyLi5vJ494hYVNro2oiYXMo3L4+Xl/0zm6x3L0XEtIhYGBEPlnPqEM+l9UXE2eXvbWlEXB0RW3g+QUR8PiIej4iltbJhnz8RcXo5/qGIOL3bz9qUDdBOF5W/u3sj4oaImFbb97HSTssi4qha+Zj9LOzWRrV9H46IjIgdyuPRPZcy069hfAETgf8FZgGTgXuAvZuuV4PtsRMwu2y/AvgJsDfwKeC8Un4ecGHZPhb4BhDAwcCipn+HHrbVOcCXgZvL4+uAU8r2ZcBfle33ApeV7VOAa5uuew/b6AvAu8r2ZGCa59J6bTQDWAFMqZ1H7/B8SoA/BmYDS2tlwzp/gO2An5bv25btbZv+3XrQTkcCk8r2hbV22rt8zm0O7F4+/yaO9c/Cbm1UyncFvkV1r9YdenEu2aM2fAcByzPzp5n5HHANML/hOjUmMx/LzLvL9lPAA1QfJPOpPnQp308o2/OBL2blTmBaROzU42r3XETsArwZ+Fx5HMA8qnVvYf026rTdQuDwcvyYFhFbU705XgGQmc9l5m/wXOpmEjAlIiYBU4HH8HwiM+8Aft2veLjnz1HArZn568x8ArgVOHr0a9873dopM2/JzBfKwzuBXcr2fOCazPxdZq4AllN9Do7pz8IBziWAS4CPAvUL/Ef1XDKoDd8M4JHa41WlbNwrQyr7A4uAV2bmY1CFOWDHcth4bb9PU/1xv1Qebw/8pvbGWG+HtW1U9q8px491s4DVwJVliPhzEbElnkt9ZOajwMXASqqAtga4C8+ngQz3/BmX51U/Z1D1EIHttFZEHA88mpn39Ns1qm1kUBu+bv+JjvupsxGxFfBV4IOZ+eSGDu1SNqbbLyKOAx7PzLvqxV0OzSHsG8smUQ01fDYz9weephqqGsi4bKdyjdV8qmGonYEtgWO6HDrez6fBDNQu47q9IuJ84AXgS52iLoeNu3aKiKnA+cDfddvdpWzE2sigNnyrqMaoO3YBft5QXVohIjajCmlfyszrS/EvO8NQ5fvjpXw8tt8fAsdHxMNUwwPzqHrYppWhK+jbDmvbqOzfhu5d8GPNKmBVZi4qjxdSBTfPpb6OAFZk5urMfB64HpiL59NAhnv+jNfzinKx+3HA27JcZIXt1PFqqn+O7inv5bsAd0fE7zHKbWRQG74fAnuWGVaTqS7OvbHhOjWmXOtyBfBAZv5rbdeNQGeGy+nA12vlp5VZMgcDazrDEmNVZn4sM3fJzJlU58t3MvNtwO3ASeWw/m3UabuTyvFj9j/Vjsz8BfBIROxVig4HfoznUn8rgYMjYmr5++u0k+dTd8M9f74FHBkR25beyyNL2ZgWEUcD5wLHZ+YztV03AqeU2cO7A3sC/8M4+yzMzPsyc8fMnFney1dRTaT7BaN9LjUxm2JT/6Ka4fETqhkv5zddn4bb4lCqrtx7gSXl61iqa2BuAx4q37crxwfw76Xt7gPmNP079Li9DmPdrM9ZVG94y4GvAJuX8i3K4+Vl/6ym693D9tkPWFzOp69RzZTyXFq/nf4eeBBYCvwn1Yy8cX8+AVdTXbf3PNUH6Zkbc/5QXaO1vHy9s+nfq0fttJzqeqrO+/hltePPL+20DDimVj5mPwu7tVG//Q+zbtbnqJ5LrkwgSZLUUg59SpIktZRBTZIkqaUMapIkSS1lUJMkSWopg5okSVJLGdQkjaqIeDEilkTE0oj4SrnD98a8zm9HqD4XRMSHByjPiNijVnZ2KZvzMn/mzPI676uVXRoR73g5r1t7re++3DpKaieDmqTR9mxm7peZ+wDPAQuartAG3Ed1486Ok6huJjsSHgc+UG4O2hq11QwktZBBTVIv/TewB0BEfC0i7oqI+yPi3aXszIi4pHNwRPxlRNRXvKDc/fui0kN3X0S8tZRvFRG3RcTdpXx+7TnnR8SyiPg2sBcD+xrVOppExCyqBcxXl8cTI+Kq2s89u5QfGBH3RsQPOvUa4LVXU91w9fT+O+o9YhGxQ1mihoh4R2mnmyJiRUT8dUScE9Wi9XdGxHa1l3l7RHy/1O+g8vwtI+LzEfHD8pz5tdf9SkTcBNyygfaQ1DCDmqSeKD03x1D1WgGckZkHAHOA90fE9lRroR4f1fqxAO8Eruz3Un9KtYLBvlTrXl5U1nD8P+AtmTkbeBPwLyXUHUDVS7Z/ee6BG6jmk1TLWO0D/DlwbW3ffsCMzNwnM19Xq9eVwILMPAR4cZBm+GfgQxExcZDj6vYBTgUOAj4BPJPVovU/AE6rHbdlZs4F3gt8vpSdT7Vk1IFUbXJRRGxZ9h0CnJ6Z84ZRF0k9ZlCTNNqmRMQSqqWhVlKtDQtVOLsHuJNq4eI9M/Np4DvAcRHxWmCzzLyv3+sdClydmS9m5i+B71GFrwA+GRH3At8GZgCvBP4IuCEzn8nMJxl8PcJrqILdCcANtfKfArMi4t/KuohPRsQ04BWZ+f1yzJc39MKZuYJqGadTB6lD3e2Z+VRmrqbq4buplN8HzKwdd3X5GXcAW5e6HQmcV9r/u1TLSb2qHH9rZo6nxdmlTZLXJkgabc9m5n71gog4jKo37JDMfCYivksVIgA+B/wN1VqW/XvToApk3bwNmA4ckJnPl+HDzmsOZ628m4CLgMWZ+WS17jlk5hMRsS9wFHAWcDLwoWG8bscngYXAHbWyF1j3j/MW/Y7/XW37pdrjl+j7Ht7/d0yqtjoxM5fVd0TEG4Cnh11zST1nj5qkJmwDPFFC2muBgzs7MnMRVQ/bqZReon7uAN5arhmbDvwxVS/VNsDjJaS9CditdvxbImJKRLwC+JMNVSwznwXOpRpmXCsidgAmZOZXgb8FZmfmE8BTEdGp/ykMIjMfpJqgcFyt+GHggLJ90mCvMYDOtXqHAmsycw3wLeB9UdJmROy/ka8tqSH2qElqwjeBBWWYchnV8GfddcB+JQj1dwPV9VX3UPUafTQzfxERXwJuiojFwBKqHjky8+6IuLaU/YxqQsMGZeY1XYpnAFdGROcf3I+V72cC/xERT1MNL64Z7PWpQuCPao8vBq6LiL+gGvrdGE9ExPeBrYEzStk/Ap8G7i1h7WH6BkRJLReZwxkRkKTRFxE3A5dk5m1N12UwEbFVZv62bJ8H7JSZH2i4WpLGCIc+JbVGREyLiJ9QXdfW+pBWvDnKDX2pJi78U9MVkjR22KMmSZLUUvaoSZIktZRBTZIkqaUMapIkSS1lUJMkSWopg5okSVJLGdQkSZJa6v8BMkVZpVnJPxUAAAAASUVORK5CYII=\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "# Check to see that from three different runs.. the LiDAR Tag process is not deterministic\n", + "mpld3.enable_notebook()\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data_ctrl1.total_num_clusters, label='Playback 1')\n", + "plt.plot(data_ctrl2.total_num_clusters, label='Playback 2')\n", + "plt.plot(data_ctrl3.total_num_clusters, label='Playback 3')\n", + "plt.plot(data_ctrl4.total_num_clusters, label='Playback 4')\n", + "plt.legend()\n", + "plt.title(\"Multiple runs of Cluster (Control)\")\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data_ctrl1.total_num_clusters, label=\"Dense Thresholding\")\n", + "plt.plot(data_zthr.total_num_clusters, label=\"W/Z Thresholding\")\n", + "plt.plot(data_zythr.total_num_clusters, label=\"W/ZY Thresholding\")\n", + "plt.plot(data_zyxthr.total_num_clusters, label=\"W/ZYX Thresholding\")\n", + "plt.title(\"Total Number of Clusters Before Pruning\")\n", + "plt.legend()\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "remaining_clusters_ctrl = data_ctrl1.total_num_clusters - data_ctrl1.pt_rm_clusters\n", + "remaining_clusters_zthr = data_zthr.total_num_clusters - data_zthr.pt_rm_clusters\n", + "remaining_clusters_zythr = data_zythr.total_num_clusters - data_zythr.pt_rm_clusters\n", + "remaining_clusters_zyxthr = data_zyxthr.total_num_clusters - data_zyxthr.pt_rm_clusters\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(remaining_clusters_ctrl, label=\"Dense Thresholding\")\n", + "plt.plot(remaining_clusters_zthr, label=\"W/Z Thresholding\")\n", + "plt.plot(remaining_clusters_zythr, label=\"W/ZY Threhsolding\")\n", + "plt.plot(remaining_clusters_zyxthr, label=\"W/ZYX Thresholding\")\n", + "plt.title(\"Remaining Clusters after Point Removal Check\")\n", + "plt.legend()\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Clusters\");" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "plt.plot(data_ctrl1.clusters_in_pc, label=\"Dense Thresholding\")\n", + "plt.plot(data_zthr.clusters_in_pc, label=\"W/Z Thresholding\")\n", + "plt.plot(data_zythr.clusters_in_pc, label=\"W/ZY Thresholding\")\n", + "plt.plot(data_zythr.clusters_in_pc, label=\"W/ZYX Thresholding\")\n", + "plt.title(\"Final number of Tags Decoded)\")\n", + "plt.legend()\n", + "plt.xlabel(\"Payload Msg Number\")\n", + "plt.ylabel(\"Number of Tags\");" + ] + }, + { + "cell_type": "code", + "execution_count": 18, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/html": [ + "\n", + "\n", + "\n", + "\n", + "
\n", + "" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [ + "mpld3.enable_notebook()\n", + "\n", + "num_pcs = []\n", + "num_pcs.append(data_ctrl1.clusters_in_pc.size)\n", + "num_pcs.append(data_zthr.clusters_in_pc.size)\n", + "num_pcs.append(data_zythr.clusters_in_pc.size)\n", + "num_pcs.append(data_zyxthr.clusters_in_pc.size)\n", + "num_pcs = np.array(num_pcs)\n", + "ind = np.array(list(range(1,len(num_pcs)+1)))\n", + "\n", + "fig = plt.gcf()\n", + "fig.set_size_inches(10,6)\n", + "\n", + "axes = plt.gca()\n", + "plt.bar(ind, num_pcs)\n", + "plt.title(\"Number of Payloads Processed\")\n", + "plt.xticks(ind, ('Control', 'W/Z', 'W/ZY', 'W/ZYX'));\n", + "plt.ylabel(\"Number of Payloads\")\n", + "plt.xlabel(\"Simulation Type\")\n", + "\n", + "axes.set_ylim([int(np.amin(num_pcs) * 0.9), None]);" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "[]" + ] + }, + "execution_count": 13, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "\n" + ], + "text/plain": [ + "
" + ] + }, + "metadata": { + "needs_background": "light" + }, + "output_type": "display_data" + } + ], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.7.5" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/src/lidar_tag.cc b/src/lidar_tag.cc deleted file mode 100644 index b410c88..0000000 --- a/src/lidar_tag.cc +++ /dev/null @@ -1,2790 +0,0 @@ -/* Copyright (C) 2013-2020, The Regents of The University of Michigan. - * All rights reserved. - * This software was developed in the Biped Lab (https://www.biped.solutions/) - * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may - * be available under alternative licensing terms; contact the address above. - * 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 Regents of The University of Michigan. - * - * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) - * WEBSITE: https://www.brucerobot.com/ - */ - - -#include -#include -#include -#include -#include -#include -#include -#include - -#include // SVD -#include // matrix exponential -#include // tensor output - -#include // package -#include "lidar_tag.h" -#include "apriltag_utils.h" -#include "utils.h" -#include "tag49h14.h" -#include "tag16h5.h" - -#include -#include // std::sort -#include /* sqrt, pow(a,b) */ -#include /* clock_t, clock, CLOCKS_PER_SEC */ -#include /* srand, rand */ -#include // log files - - -/* CONSTANT */ -#define SQRT2 1.41421356237 -#define MAX_INTENSITY 255 -#define MIN_INTENSITY 0 - -using namespace std; - -namespace BipedLab { - LiDARTag::LiDARTag(): - _nh("~"), - _point_cloud_received(0), - _pub_frame("velodyne"), // what frame of the published pointcloud should be - _stop(0) // Just a switch for exiting this program while using valgrind - { - LiDARTag::_getParameters(); - cout << "\033[1;32m\n\n===== loading tag family ===== \033[0m\n"; - LiDARTag::_initDecoder(); - - if (_decode_method!=0 && _decode_method!=1){ - ROS_ERROR("Please use 0 or 1 for decode_method in the launch file"); - ROS_INFO_STREAM("currently using: "<< _decode_method); - } - cout << "\033[1;32m=========================== \033[0m\n"; - cout << "\033[1;32m=========================== \033[0m\n"; - - ROS_INFO("ALL INITIALIZED!"); - _LiDAR1_sub = _nh.subscribe(_pointcloud_topic, 50, - &LiDARTag::_pointCloudCallback, this); - _edge_pub = _nh.advertise("EdgedPC", 10); - _cluster_pub = _nh.advertise("DetectedPC", 10); - _payload_pub = _nh.advertise("Payload", 10); - _boundary_marker_pub = _nh.advertise( "BoundaryMarker", 10); - _cluster_marker_pub = _nh.advertise("ClusterMarker", 10); - _payload_marker_pub = _nh.advertise("PayloadEdges", 10); - _payload_grid_pub = _nh.advertise("Grid", 10); - _payload_grid_line_pub = _nh.advertise("GridLine", 10); - _lidartag_pose_pub = _nh.advertise("LiDARTagPose", 1); - - boost::thread RosSpin(&LiDARTag::_rosSpin, this); // put ros spin into a background thread - - ROS_INFO("Waiting for pointcloud data"); - LiDARTag::_waitForPC(); - - // Exam the minimum distance of each point in a ring - ROS_INFO("Analyzing system"); - LiDARTag::_analyzeLiDARDevice(); - boost::thread ExtractionSpin(&LiDARTag::_mainLoop, this); - ExtractionSpin.join(); - RosSpin.join(); - } - - - /* - * A function to get all parameters from a roslaunch - * if not get all parameters then it will use hard-coded parameters - */ - void LiDARTag::_getParameters(){ - bool GotSleepToDisplay = ros::param::get("sleep_to_display", _sleep_to_display); - bool GotSleepTimeForVis = ros::param::get("sleep_time_for_visulization", _sleep_time_for_vis); - bool GotValgrindCheck = ros::param::get("valgrind_check", _valgrind_check); - bool GotFakeTag = ros::param::get("fake_data", _fake_tag); - - bool GotCSV = ros::param::get("write_csv", _write_CSV); - bool GotDecodeId = ros::param::get("decode_id", _id_decoding); - bool GotAssignId = ros::param::get("assign_id", _assign_id); - - bool GotAdaptiveThresholding = ros::param::get("adaptive_thresholding", _adaptive_thresholding); - bool GotCollectData = ros::param::get("collect_data", _collect_dataset); - - bool GotLidarTopic = ros::param::get("pointcloud_topic", _pointcloud_topic); - bool GotBeamNum = ros::param::get("beam_number", _beam_num); - bool GotSize = ros::param::get("tag_size", _payload_size); - - bool GotTagFamily = ros::param::get("tag_family", _tag_family); - bool GotTagHamming = ros::param::get("tag_hamming_distance", _tag_hamming_distance); - bool GotMaxDecodeHamming = ros::param::get("max_decode_hamming", _max_decode_hamming); - bool GotBlackBorder = ros::param::get("black_border", _black_border); - - bool GotDistanceBound = ros::param::get("distance_bound", _distance_bound); - bool GotIntensityBound = ros::param::get("intensity_bound", _intensity_threshold); - bool GotDepthBound = ros::param::get("depth_bound", _depth_threshold); - bool GotFineClusterThreshold = ros::param::get("fine_cluster_threshold", _fine_cluster_threshold); - bool GotVerticalFOV = ros::param::get("vertical_fov", _vertical_fov); - bool GotFillInGapThreshold = ros::param::get("fill_in_gap_threshold", _filling_gap_max_index); - bool GotFillInMaxPointsThreshold = ros::param::get("fill_in_max_points_threshold", _filling_max_points_threshold); - bool GotPointsThresholdFactor = ros::param::get("points_threshold_factor", _points_threshold_factor); - bool GotLineIntensityBound = ros::param::get("line_intensity_bound", _line_intensity_bound); - bool GotPayloadIntensityThreshold = ros::param::get("payload_intensity_threshold", _payload_intensity_threshold); - - bool GotLatestModel = ros::param::get("latest_model", _latest_model); - bool GotWeightPath = ros::param::get("weight_path", _weight_path); - - bool GotMaxPointsOnPayload = ros::param::get("max_points_on_payload", _max_point_on_payload); - bool GotXYZRI = ros::param::get("xyzri", _XYZRI); - bool GotMinPerGrid = ros::param::get("min_retrun_per_grid", _min_returns_per_grid); - bool GotDecodeMethod = ros::param::get("decode_method", _decode_method); - bool GotGridViz = ros::param::get("grid_viz", _grid_viz); - - bool Pass = utils::checkParameters(33, GotFakeTag, GotLidarTopic, GotBeamNum, - GotDecodeId, GotAssignId, GotCSV, - GotDistanceBound, GotIntensityBound, GotDepthBound, - GotSize, GotTagFamily, GotTagHamming, GotMaxDecodeHamming, - GotFineClusterThreshold, GotVerticalFOV, - GotFillInGapThreshold, GotFillInMaxPointsThreshold, - GotPointsThresholdFactor, GotLineIntensityBound, - GotAdaptiveThresholding, GotCollectData, GotSleepToDisplay, - GotSleepTimeForVis, GotValgrindCheck, - GotLatestModel, GotWeightPath, - GotMaxPointsOnPayload, GotXYZRI, GotMinPerGrid, GotDecodeMethod, - GotGridViz); - - if (!Pass){ - // TODO: check compleness - cout << "\033[1;32m=========================== \033[0m\n"; - cout << "use hard-coded parameters\n"; - cout << "\033[1;32m=========================== \033[0m\n"; - - // Default value - _pointcloud_topic = "/velodyne_points"; - _beam_num = 32; - _distance_bound = 7; // for edge gradient - _intensity_threshold = 2; // for edge gradient - _depth_threshold = 0.5; // for edge gradient - _payload_intensity_threshold = 30; - _payload_size = 0.15; - - _tag_family = 16; - _tag_hamming_distance = 5; - _max_decode_hamming = 2; - - _fine_cluster_threshold = 20; // if the points in a cluster is small than this, it'd get dropped - _vertical_fov = 40; - - // When fill in the cluster, if it the index is too far away then drop it - // TODO:Need a beteer way of doing it! - _filling_gap_max_index = 200; - _filling_max_points_threshold = 4500; - - _line_intensity_bound = 1000; // To determine the payload edge - - // if the points on a "valid" tag is less than this factor, then remove - // it (the higher, the looser) - _points_threshold_factor = 1.3; - _adaptive_thresholding = 0; - _collect_dataset = 1; - - _sleep_to_display = 1; - _sleep_time_for_vis = 0.05; - _valgrind_check = 0; - _black_border = 2; - _fake_tag = 0; - - _latest_model = "-337931"; - _weight_path = "/weight/"; - _max_point_on_payload = 150; - _XYZRI = 4 ; - _min_returns_per_grid = 3; - _decode_method = 2; - _grid_viz = 1; - } - else{ - cout << "\033[1;32m=========================== \033[0m\n"; - cout << "use parameters from the launch file\n"; - cout << "\033[1;32m=========================== \033[0m\n"; - } - - _threshold = _payload_size/4; // point association threshold (which cluster the point belongs to?) - _RANSAC_threshold = _payload_size/10; - - ROS_INFO("Subscribe to %s\n", _pointcloud_topic.c_str()); - ROS_INFO("Use %i-beam LiDAR\n", _beam_num); - ROS_INFO("_intensity_threshold: %f \n", _intensity_threshold); - ROS_INFO("_depth_threshold: %f \n", _depth_threshold); - ROS_INFO("_payload_size: %f \n", _payload_size); - ROS_INFO("_vertical_fov: %i \n", _vertical_fov); - ROS_INFO("_fine_cluster_threshold: %i \n", _fine_cluster_threshold); - ROS_INFO("_filling_gap_max_index: %i \n", _filling_gap_max_index); - ROS_INFO("_filling_max_points_threshold: %i \n", _filling_max_points_threshold); - ROS_INFO("_points_threshold_factor: %f \n", _points_threshold_factor); - ROS_INFO("_adaptive_thresholding: %i \n", _adaptive_thresholding); - ROS_INFO("_collect_dataset: %i \n", _collect_dataset); - ROS_INFO("_decode_method: %i \n", _decode_method); - ROS_INFO("Threshold_: %f \n", _threshold); - ROS_INFO("_RANSAC_threshold: %f \n", _RANSAC_threshold); - - usleep(2e6); - } - - - /* - * Main loop - */ - void LiDARTag::_mainLoop(){ - ROS_INFO("Start edge extraction"); - //ros::Rate r(10); // 10 hz - ros::Duration duration(_sleep_time_for_vis); - int Count = 0; // just to caculate average speed - clock_t StartAve = clock(); - pcl::PointCloud::Ptr ClusterPC(new pcl::PointCloud); - pcl::PointCloud::Ptr PayloadPC(new pcl::PointCloud); - ClusterPC->reserve(_point_cloud_size); - - // XXX Tunalbe - PayloadPC->reserve(_point_cloud_size); - int valgrind_check = 0; - while (ros::ok()) { - _lidartag_pose_array.detections.clear(); - _timing = {clock(), clock(), clock(), 0,0,0,0,0,0,0,0,0}; - - // Try to take a pointcloud from the buffer - std::vector> OrderedBuff = LiDARTag::_getOrderBuff(); - if (OrderedBuff.empty()){ - continue; - } - - // A vector of clusters - vector ClusterBuff; - - pcl::PointCloud::Ptr ExtractedEdgesPC = LiDARTag::_lidarTagDetection(OrderedBuff, - ClusterBuff); - ClusterPC->clear(); - PayloadPC->clear(); - - // Prepare results for rviz - visualization_msgs::MarkerArray ClusterMarkers; - LiDARTag::_clusterToPclVectorAndMarkerPublisher(ClusterBuff, ClusterPC, PayloadPC, ClusterMarkers); - - // publish lidartag poses - _lidartag_pose_pub.publish(_lidartag_pose_array); - - // publish results for rviz - LiDARTag::_publishPC(ExtractedEdgesPC, _pub_frame, string("edge")); - LiDARTag::_publishPC(ClusterPC, _pub_frame, string("Cluster")); - if (_collect_dataset){ - if (_result_statistics.remaining_cluster_size==1) - LiDARTag::_publishPC(PayloadPC, _pub_frame, string("Payload")); - else if (_result_statistics.remaining_cluster_size>1) - cout << "More than one!! " << endl; - else - cout << "Zero!! " << endl; - } - else - LiDARTag::_publishPC(PayloadPC, _pub_frame, string("Payload")); - - //exit(0); - if (_sleep_to_display) duration.sleep(); - Count++; - _timing.total_time = utils::spendTime(clock(), _timing.start_total_time); - ROS_INFO_STREAM("Hz (total): " << 1e3/_timing.total_time); - cout << "\033[1;31m====================================== \033[0m\n"; - if (_valgrind_check){ - valgrind_check++; - if (valgrind_check > 0) { - _stop = 1; - break; - } - } - } - } - - - /* - * A function to get pcl OrderedBuff from a ros sensor-msgs form of pointcould queue - * */ - std::vector> LiDARTag::_getOrderBuff(){ - _point_cloud1_queue_lock.lock(); - if (_point_cloud1_queue.size()==0) { - _point_cloud1_queue_lock.unlock(); - //ros::spinOnce(); - //cout << "Pointcloud queue is empty" << endl; - //cout << "size: " << Empty.size() << endl; - vector> Empty; - return Empty; - } - ROS_INFO_STREAM("Queue size: " << _point_cloud1_queue.size()); - - sensor_msgs::PointCloud2ConstPtr msg = _point_cloud1_queue.front(); - _current_scan_time = msg->header.stamp; - - // Convert to sensor_msg to pcl type - pcl::PointCloud::Ptr PclPointcloud(new pcl::PointCloud); - pcl::fromROSMsg(*msg, *PclPointcloud); - _point_cloud1_queue.pop(); - _point_cloud1_queue_lock.unlock(); - - std::vector> OrderedBuff(_beam_num); - - // Ordered pointcloud with respect to its own ring number - _fillInOrderedPC(PclPointcloud, OrderedBuff); - _point_cloud_size = PclPointcloud->size(); - - return OrderedBuff; - } - - - /* - * A function to get a LiDAR system parameters such as max, min points per scan - * and how many points per ring - * The data format is: - * - * (A) PointCountTable: - * PointCountTable[Scan][Ring] - * ----------------------------------------- - * 1 2 3 4 5 6 7 ... scan - * ----------------------------------------- - * 0 17xx ... - * ----------------------------------------- - * 1 16xx ... - * ----------------------------------------- - * 2 - * . - * . - * . - * 31 - * ring - * - * - * (B) MaxMinTable: - * ---------------------------------------- - * 1 2 3 .... scan - * Max Max Max - * Min Min Min - * --------------------------------------- - */ - void LiDARTag::_analyzeLiDARDevice(){ - clock_t begin = clock(); - int NumberOfScan = 0; - _LiDAR_system.point_count_table.resize(50); - _LiDAR_system.ring_average_table.reserve(_beam_num); - - // Initialize the table - MaxMin_t max_min{100000, -1, -1}; // min, ave, max - - for (int j=0; j<_beam_num; ++j){ - _LiDAR_system.ring_average_table.push_back(max_min); - } - - // Calulate for each scan with a few seconds - while (ros::ok()){ - std::vector> OrderedBuff = LiDARTag::_getOrderBuff(); - if (OrderedBuff.empty()){ - continue; - } - LiDARTag::_maxMinPtsInAScan(_LiDAR_system.point_count_table[NumberOfScan], - _LiDAR_system.max_min_table, - _LiDAR_system.ring_average_table, - OrderedBuff); - NumberOfScan++; - clock_t end = clock(); - if (((double) (end-begin)/ CLOCKS_PER_SEC) > 3){ - break; - } - } - for (auto i=_LiDAR_system.ring_average_table.begin(); i!=_LiDAR_system.ring_average_table.end(); ++i){ - (*i).average /= NumberOfScan; - } - - LiDARTag::_pointsPerSquareMeterAtOneMeter(); - - - - - // Check values of pointtable and maxmintable - // int k = 0; - // for (auto i=_LiDAR_system.PointCountTable.begin(); i!=_LiDAR_system.PointCountTable.end(); ++i, ++k){ - // cout << "Vector[" << k << "]:" << endl; - // for (auto j=(*i).begin(); j!=(*i).end(); ++j){ - // cout << "points: " << *j << endl; - // } - // } - - // k=0; - // for (auto i=_LiDAR_system.MaxMinTable.begin(); i!=_LiDAR_system.MaxMinTable.end(); ++i, ++k){ - // cout << "At scan [" << k << "]" << endl; - // cout << "Max: " << (*i).Max << endl; - // cout << "Min: " << (*i).Min << endl; - // } - - // k=0; - // for (auto i=_LiDAR_system.ring_average_table.begin(); i!=_LiDAR_system.ring_average_table.end(); ++i, ++k){ - // cout << "At ring [" << k << "]" << endl; - // cout << "Max: " << (*i).Max << endl; - // cout << "Ave: " << (*i).average << endl; - // cout << "Min: " << (*i).Min << endl; - // } - // exit(0); - } - - - /* - * A function to calculate how many points are supposed to be on a cluster at 1 - * meter away - */ - void LiDARTag::_pointsPerSquareMeterAtOneMeter(){ - double system_average; - - for (auto i=_LiDAR_system.ring_average_table.begin(); - i!=_LiDAR_system.ring_average_table.end(); ++i){ - system_average += (*i).average; - } - system_average /= _LiDAR_system.ring_average_table.size(); - _LiDAR_system.beam_per_vertical_radian = _beam_num / utils::deg2Rad(_vertical_fov); - _LiDAR_system.point_per_horizontal_radian = system_average / utils::deg2Rad(360); - } - - - /* - * A function to get a number of points on a given-distance tag or object - */ - int LiDARTag::_areaPoints(const double &Distance, const double &ObjWidth, const double &ObjHeight){ - double WAngle = ObjWidth * (1 + SQRT2) / abs(Distance); - - if (WAngle>=1) return (int) 1e6; // return big number to reject the cluster - - double HAngle = ObjHeight * (1 + SQRT2) / abs(Distance); - if (HAngle>=1) return (int) 1e6; // return big number to reject the cluster - - double HorizontalAngle = asin(WAngle); // in radian - double VerticalAngle = asin(HAngle); // in radian - int NumOfVerticalRing = floor(VerticalAngle * _LiDAR_system.beam_per_vertical_radian); - int NumOfHorizontalPoints = floor(HorizontalAngle * _LiDAR_system.point_per_horizontal_radian); - - // use 3 instead of 2 becasue of we assume the tag would be put in the dense - // region of LiDAR (LiDAR is denser in the middle) - int Area = floor(3 * (NumOfVerticalRing * NumOfHorizontalPoints) / (1 + SQRT2)); - - //cout << "distance: " << abs(Distance) << endl; - //cout << "HorizontalAngle: " << HorizontalAngle << endl; - //cout << "VerticalAngle: " << VerticalAngle << endl; - - //cout << "NumOfVerticalRing: " << NumOfVerticalRing << endl; - //cout << "NumOfHorizontalPoints: " << NumOfHorizontalPoints << endl; - //cout << "Area: " << Area << endl; - - return Area; - } - - - /* - * A function to find maximum points and minimum points in a single scan, i.e. to - * find extrema within 32 rings - */ - void LiDARTag::_maxMinPtsInAScan(std::vector &PointCountTable, - std::vector &MaxMinTable, - std::vector &RingAverageTable, - const std::vector>& OrderedBuff){ - - // every scan should have different largest/ smallest numbers - int Largest = -1; - int Smallest = 100000; - MaxMin_t max_min; - - int i = 0; - for (auto Ring=OrderedBuff.begin(); Ring!=OrderedBuff.end(); ++Ring){ - int RingSize = (*Ring).size(); - PointCountTable.push_back(RingSize); - - // first time (we had initialized with -1) - if (RingAverageTable[i].average<0) { - RingAverageTable[i].average = RingSize; - } - else{ - RingAverageTable[i].average = (RingAverageTable[i].average + RingSize); - } - - if (RingAverageTable[i].maxRingSize){ - RingAverageTable[i].min = RingSize; - } - - if (RingSize > Largest) { - Largest = RingSize; - max_min.max = RingSize; - } - - if (RingSize < Smallest) { - Smallest = RingSize; - max_min.min = RingSize; - } - i++; - } - MaxMinTable.push_back(max_min); - } - - - /* - * A function to transfer pcl msgs to ros msgs and then publish - * WhichPublisher should be a string of "organized" or "original" regardless - * lowercase and uppercase - */ - void LiDARTag::_publishPC(const pcl::PointCloud::Ptr &SourcePC, - const std::string &Frame, string WhichPublisher){ - utils::tranferToLowercase(WhichPublisher); // check letter cases - sensor_msgs::PointCloud2 PCsWaitedToPub; - pcl::toROSMsg(*SourcePC, PCsWaitedToPub); - PCsWaitedToPub.header.frame_id = Frame; - - try { - if (WhichPublisher=="edge") _edge_pub.publish(PCsWaitedToPub); - else if (WhichPublisher=="original") _original_pc_pub.publish(PCsWaitedToPub); - else if (WhichPublisher=="cluster") _cluster_pub.publish(PCsWaitedToPub); - else if (WhichPublisher=="payload") _payload_pub.publish(PCsWaitedToPub); - else { - throw "No such Publisher exists"; - } - } - catch (const char* msg){ - cout << "\033[1;31m========================= \033[0m\n"; - cerr << msg << endl; - cout << "\033[1;31m========================= \033[0m\n"; - exit(-1); - } - } - - - /* [basic ros] - * A function to push the received pointcloud into a queue in the class - */ - void LiDARTag::_pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr &pc){ - _point_cloud_received = 1; // flag to make sure it receives a pointcloud at the very begining of the program - _point_cloud_header = pc->header; - boost::mutex::scoped_lock(_point_cloud1_queue_lock); - _point_cloud1_queue.push(pc); - } - - - /* - * A function to make sure the program has received at least one pointcloud at - * the very start of this program - */ - inline - void LiDARTag::_waitForPC(){ - while (ros::ok()){ - if (_point_cloud_received) { - ROS_INFO("Got pointcloud data"); - return; - } - ros::spinOnce(); - } - } - - - /* - * A function to slice the Veloydyne full points to sliced pointed based on ring - * number - * */ - inline - void LiDARTag::_fillInOrderedPC(const pcl::PointCloud::Ptr &PclPointcloud, - std::vector>& OrderedBuff) { - LiDARPoints_t LiDARPoint; - int index [_beam_num] = {0}; - for (auto && p : *PclPointcloud) { - LiDARPoint.point = p; - LiDARPoint.index = index[p.ring]; - index[p.ring] += 1; - OrderedBuff[p.ring].push_back(LiDARPoint); - } - } - - - /* - * Main function - */ - pcl::PointCloud::Ptr - LiDARTag::_lidarTagDetection(const std::vector>& OrderedBuff, - std::vector &ClusterBuff){ - - _timing.start_computation_time = clock(); - pcl::PointCloud::Ptr Out(new pcl::PointCloud); - Out->reserve(_point_cloud_size); - std::vector> EdgeBuff(_beam_num); // Buff to store all detected edges - - // calculate gradient for depth and intensity as well as group them into diff groups - _result_statistics = {{0, 0, 0, 0, 0, 0}, 0, 0, 0, 0}; - _timing.timing = clock(); - LiDARTag::_gradientAndGroupEdges(OrderedBuff, EdgeBuff, ClusterBuff); - _timing.edgingand_clustering_time = utils::spendTime(clock(), _timing.timing); - - _timing.timing = clock(); - // transform from a vector of vector (EdgeBuff) into a pcl vector (out) - boost::thread BuffToPclVectorThread(&LiDARTag::_buffToPclVector, this, boost::ref(EdgeBuff), Out); - _timing.to_pcl_vector_time = utils::spendTime(clock(), _timing.timing); - - - LiDARTag::_fillInCluster(OrderedBuff, ClusterBuff); - BuffToPclVectorThread.join(); - _result_statistics.point_cloud_size = _point_cloud_size; - _result_statistics.edge_cloud_size = Out->size(); - - _timing.computation_time = utils::spendTime(clock(), _timing.start_computation_time); - ROS_DEBUG_STREAM("--------------- summary ---------------"); - ROS_DEBUG_STREAM("Original cloud size: " << _result_statistics.point_cloud_size); - ROS_DEBUG_STREAM("--Edge cloud size: " << _result_statistics.edge_cloud_size); - ROS_DEBUG_STREAM("Original cluster: " << _result_statistics.original_cluster_size); - ROS_DEBUG_STREAM("--Point check Removed: " << _result_statistics.cluster_removal.removed_by_point_check); - ROS_DEBUG_STREAM("--Minimum return removed: " << _result_statistics.cluster_removal.minimum_return); - ROS_DEBUG_STREAM("--Boundary point Removed: " << _result_statistics.cluster_removal.boundary_point_check); - ROS_DEBUG_STREAM("--No Edge Removed: " << _result_statistics.cluster_removal.no_edge_check); - ROS_DEBUG_STREAM("--Not Enough for decode Removed: " << _result_statistics.cluster_removal.decoder_not_return); - ROS_DEBUG_STREAM("--Corners Removed: " << _result_statistics.cluster_removal.decoder_fail_corner); - ROS_DEBUG_STREAM("--Decode-Fail Removed: " << _result_statistics.cluster_removal.decode_fail); - ROS_DEBUG_STREAM("--Remaining Cluster: " << _result_statistics.remaining_cluster_size); - ROS_DEBUG_STREAM("computation_time Hz: " << 1/_timing.computation_time*1e3); - ROS_DEBUG_STREAM("--------------- Timing ---------------"); - ROS_DEBUG_STREAM("computation_time: " << _timing.computation_time); - ROS_DEBUG_STREAM("edgingand_clustering_time: " << _timing.edgingand_clustering_time); - ROS_DEBUG_STREAM("PointCheck: " << _timing.point_check_time); - ROS_DEBUG_STREAM("LineFitting: " << _timing.line_fitting_time); - ROS_DEBUG_STREAM("ExtractPayload: " << _timing.payload_extraction_time); - ROS_DEBUG_STREAM("NormalVector: " << _timing.normal_vector_time); - ROS_DEBUG_STREAM("PayloadDecoder: " << _timing.payload_decoding_time); - ROS_DEBUG_STREAM("_tagToRobot: " << _timing.tag_to_robot_time); - - return Out; - } - - - /* - * A function to - * (1) calculate the depth gradient and the intensity gradient at a point of a pointcloud - * (2) group detected 'edge' into different group - */ - void LiDARTag::_gradientAndGroupEdges(const std::vector>& OrderedBuff, - std::vector>& EdgeBuff, - std::vector &ClusterBuff) { - - // clock_t start = clock(); - // TODO: if suddently partial excluded, it will cause errors - for(int i=0; i<_beam_num; i++) { - for(int j=2; j _distance_bound || - std::abs(point.y) > _distance_bound || - std::abs(point.z) > _distance_bound) continue; - const auto& PointL = OrderedBuff[i][j-2].point; - const auto& PointR = OrderedBuff[i][j+2].point; - - double DepthGrad = std::max((PointL.getVector3fMap()-point.getVector3fMap()).norm(), - (point.getVector3fMap()-PointR.getVector3fMap()).norm()); - - // double IntenstityGrad = std::max(std::abs(PointL.intensity - point.intensity), - // std::abs(point.intensity - PointR.intensity)); - - // if (IntenstityGrad > _intensity_threshold && - // DepthGrad > _depth_threshold) { - if (DepthGrad > _depth_threshold) { - - // Cluster the detected 'edge' into different groups - _clusterClassifier(OrderedBuff[i][j], ClusterBuff); - - // push the detected point that is an edge into a buff - LiDARPoints_t LiDARPoints = {OrderedBuff[i][j].point, OrderedBuff[i][j].index, - DepthGrad, 0}; - EdgeBuff[i].push_back(LiDARPoints); - } - } - } - // clock_t end = clock(); - // cout << "extraction hz: " << 1/ (((double) (end - start))/clocks_per_sec) << endl; - } - - - /* - * A function to - * (1) remove invalid cluster based on the index is too far or not - * (2) fill in the points between index of edges - * (3) after filling, if the points are too less (based on the analyzed system - * and given distant of the cluster), then remove this cluster - * (4) Adaptive thresholding (Maximize and minimize intensity) by comparing - * with the average value - */ - void LiDARTag::_fillInCluster(const std::vector>& OrderedBuff, - std::vector &ClusterBuff){ - - _result_statistics.original_cluster_size = ClusterBuff.size(); - _result_statistics.remaining_cluster_size = ClusterBuff.size(); - for (int i=0; i_filling_gap_max_index) continue; - - // push points between index into the cluster - for (int k=MinIndex+1; k < MaxIndex; ++k){ // remove minimum index itself (it has been in the cloud already) - ClusterBuff[i].data.push_back(OrderedBuff[j][k]); - //cout << "point added:" << k << endl; - } - } - - // If the points in this cluster after filling are still less than the - // factored threshold, then remove it - _timing.timing = clock(); - if(!_clusterPointsCheck(ClusterBuff[i])){ - _timing.point_check_time += utils::spendTime(clock(), _timing.timing); - //cout << "cluster removed" << endl; - ClusterBuff[i].valid = 0; - //ClusterBuff.erase(ClusterBuff.begin()+i); - // _debug_cluster.point_check.push_back(&ClusterBuff[i]); - //i--; - _result_statistics.remaining_cluster_size -= 1; - _result_statistics.cluster_removal.removed_by_point_check ++; - } - // Adaptive thresholding (Maximize and minimize intensity) by comparing - // with the average value - else { - _timing.point_check_time += utils::spendTime(clock(), _timing.timing); - //boost::thread BuffToPclVectorThread(&LiDARTag::AdaptiveThresholding, this, boost::ref(ClusterBuff[i])); - if(!LiDARTag::_adaptiveThresholding(ClusterBuff[i])) { - ClusterBuff[i].valid = 0; - _result_statistics.remaining_cluster_size -= 1; - // ClusterBuff.erase(ClusterBuff.begin()+i); - // i--; - } - } - } - } - - - /* - * A function to - * (1) do adaptive thresholding (Maximize and minimize intensity) by comparing - * with the average value and - * (2) sort points with ring number and re-index with current cluster into - * tag_edges vector so as to do regression boundary lines - * (3) It will *remove* if linefitting fails - */ - bool LiDARTag::_adaptiveThresholding(ClusterFamily_t &Cluster){ - Cluster.ordered_points_ptr.resize(_beam_num); - Cluster.payload_right_boundary_ptr.resize(_beam_num); - Cluster.payload_left_boundary_ptr.resize(_beam_num); - - for (int k=0; kpoint.intensity = Cluster.data[k].point.intensity/Cluster.max_intensity.intensity; - // Calucate "biased" average intensity value - // if (ClusterPointPtr->point.intensity > MIN_INTENSITY) - // Cluster.accumulate_intensity_of_each_ring[ClusterPointPtr->point.ring] += ClusterPointPtr->point.intensity; - // else - // Cluster.accumulate_intensity_of_each_ring[ClusterPointPtr->point.ring] -= MAX_INTENSITY; // Punish if it is black - - Cluster.ordered_points_ptr[ClusterPointPtr->point.ring].push_back(ClusterPointPtr); - } - - // Fit line of the cluster - _timing.timing = clock(); - if (!LiDARTag::_detectPayloadBoundries(Cluster)){ - _timing.line_fitting_time += utils::spendTime(clock(), _timing.timing); - - return false; - } - else { - _timing.line_fitting_time += utils::spendTime(clock(), _timing.timing); - _timing.timing = clock(); - _extractPayloadWOThreshold(Cluster); - _timing.payload_extraction_time += utils::spendTime(clock(), _timing.timing); - - // 2 is because this payload points is actually includes black - // boundary - if (Cluster.payload.size() < _min_returns_per_grid*std::pow((std::sqrt(_tag_family)+2*_black_border), 2)) { - //_debug_cluster.ExtractPayload.push_back(&Cluster); - _result_statistics.cluster_removal.minimum_return ++; - return false; - } - - // return true; - if (_id_decoding){ - _timing.timing = clock(); - if (LiDARTag::_decodPayload(Cluster)){ - _timing.payload_decoding_time += utils::spendTime(clock(), _timing.timing); - - _timing.timing = clock(); - Cluster.normal_vector = _estimateNormalVector(Cluster); - _timing.normal_vector_time += utils::spendTime(clock(), _timing.timing); - - _timing.timing = clock(); - LiDARTag::_tagToRobot(Cluster.cluster_id, Cluster.normal_vector, - Cluster.pose, Cluster.transform, Cluster.average); - _timing.tag_to_robot_time += utils::spendTime(clock(), _timing.timing); - return true; - } - else { - return false; - } - } - else { - LiDARTag::_decodPayload(Cluster); - - // directly assign ID - string Code(_assign_id); - uint64_t Rcode = stoull(Code, nullptr, 2); - BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &Cluster.entry); - Cluster.cluster_id = Cluster.entry.id; - - Cluster.normal_vector = _estimateNormalVector(Cluster); - LiDARTag::_tagToRobot(Cluster.cluster_id, Cluster.normal_vector, - Cluster.pose, Cluster.transform, Cluster.average); - return true; - } - } - } - - /* A function to publish pose of tag to the robot - */ - void LiDARTag::_tagToRobot(const int &cluster_id, const Eigen::Vector3f &NormalVec, - Homogeneous_t &pose, - tf::Transform &transform, const PointXYZRI &Ave){ - Eigen::Vector3f x(1, 0, 0); - Eigen::Vector3f y(0, 1, 0); - Eigen::Vector3f z(0, 0, 1); - pose.rotation = utils::qToR(NormalVec).cast (); - pose.translation << Ave.x, Ave.y, Ave.z; - - pose.yaw = utils::rad2Deg(acos(NormalVec.dot(y))); - pose.pitch = -utils::rad2Deg(acos(NormalVec.dot(x))); - pose.roll = utils::rad2Deg(acos(NormalVec.dot(z))); - - pose.homogeneous.topLeftCorner(3,3) = pose.rotation; - pose.homogeneous.topRightCorner(3,1) = pose.translation; - pose.homogeneous.row(3) << 0,0,0,1; - - static tf::TransformBroadcaster Broadcaster_; - transform.setOrigin(tf::Vector3(Ave.x, Ave.y, Ave.z)); - - // rotate to fit iamge frame - Eigen::Vector3f qr(0, std::sqrt(2)/2, 0); - float qr_w = std::sqrt(2)/2; - // Eigen::Vector3f qr(-0.5, 0.5, -0.5); - // float qr_w = 0.5; - - // Eigen::Vector3f qr(-0.5, -0.5, -0.5); - // float qr_w = 0.5; - // Eigen::Vector3f qr(std::sqrt(2)/2, 0, 0); - // float qr_w = std::sqrt(2)/2; - // Eigen::Vector3f qiCameraFrame = qr_w*NormalVec + 0*qr + qr.cross(NormalVec); // 0 is q.w of normalvec - // float qwCameraFrame = qr_w*0 - qr.dot(NormalVec); // 0 is q.w of normalvec - Eigen::Vector3f qiCameraFrame = NormalVec + 2*qr_w*(qr.cross(NormalVec)) + 2*qr.cross(qr.cross(NormalVec)); // 0 is q.w of normalvec - float qwCameraFrame = 0; // 0 is q.w of normalvec - - - Eigen::Vector3f q_i = qiCameraFrame; - double q_w = qwCameraFrame; - double norm = std::sqrt(std::pow(q_i(0), 2) + std::pow(q_i(1), 2) + std::pow(q_i(2), 2) + std::pow(q_w, 2)); - q_i = (q_i/norm).eval(); - q_w = q_w/norm; - tf::Quaternion q(q_i(0), q_i(1), q_i(2), q_w); - transform.setRotation(q); - Broadcaster_.sendTransform(tf::StampedTransform(transform, _point_cloud_header.stamp, - _pub_frame, to_string(cluster_id)+"_rotated")); - - - tf::Quaternion q2(NormalVec(0), NormalVec(1), NormalVec(2), 0); - transform.setRotation(q2); - Broadcaster_.sendTransform(tf::StampedTransform(transform, _point_cloud_header.stamp, - _pub_frame, "LiDARTag-ID" + to_string(cluster_id))); - - // publish lidar tag pose - lidartag_msgs::LiDARTagDetection lidartag_msg; //single message - lidartag_msg.id = cluster_id; - lidartag_msg.size = _payload_size; - geometry_msgs::Quaternion geo_q; - geo_q.x = q_i(0); - geo_q.y = q_i(1); - geo_q.z = q_i(2); - geo_q.w = q_w; - // cout << "R: \n" << pose.rotation << endl; - // cout << "det(R): \n" << pose.rotation.determinant() << endl; - // cout << "q: " << q_i(0) << ", " - // << q_i(1) << ", " - // << q_i(2) << ", " - // << q_w << endl; - lidartag_msg.pose.position.x = Ave.x; - lidartag_msg.pose.position.y = Ave.y; - lidartag_msg.pose.position.z = Ave.z; - lidartag_msg.pose.orientation = geo_q; - lidartag_msg.header = _point_cloud_header; - lidartag_msg.header.frame_id = std::string("lidartag_") + to_string(cluster_id); - _lidartag_pose_array.header = _point_cloud_header; - _lidartag_pose_array.detections.push_back(lidartag_msg); - // cout << "R.T*NV: " << endl << pose.rotation.transpose()*NormalVec << endl; - // cout << "H: " << endl << pose.homogeneous << endl; - - /* - Eigen::Vector3f x(1, 0, 0); - Eigen::Vector3f y(0, 1, 0); - Eigen::Vector3f z(0, 0, 1); - Eigen::Matrix3f zSkew; - zSkew << 0, -z(2), z(1), - z(2), 0, -z(0), - -z(1), z(0), 0; - Eigen::Vector3f u = zSkew*NormalVec; - //u = x.cross(NormalVec); - //u = z.cross(NormalVec); - //u = -z.cross(NormalVec); - //u = -x.cross(NormalVec); - //u = -y.cross(NormalVec); - //u = x.cross(NormalVec); - - u = (u.normalized()).eval(); - float theta = acos(z.dot(NormalVec)); - u = (u*theta).eval(); - Eigen::Matrix3f uSkew; - uSkew << 0, -u(2), u(1), - u(2), 0, -u(0), - -u(1), u(0), 0; - - pose.rotation = uSkew.exp(); - pose.translation << Ave.x, Ave.y, Ave.z; - pose.yaw = utils::rad2Deg(acos(NormalVec.dot(y))); - pose.pitch = -utils::rad2Deg(acos(NormalVec.dot(x))); - pose.roll = utils::rad2Deg(acos(NormalVec.dot(z))); - - pose.homogeneous.topLeftCorner(3,3) = pose.rotation; - pose.homogeneous.topRightCorner(3,1) = pose.translation; - pose.homogeneous.row(3) << 0,0,0,1; - - static tf::TransformBroadcaster Broadcaster_; - transform.setOrigin(tf::Vector3(Ave.x, Ave.y, Ave.z)); - Eigen::Vector3f q_i = sin(theta/2)*u; - double q_w = std::cos(theta/2); - double norm = std::sqrt(std::pow(q_i(0), 2) + std::pow(q_i(1), 2) + std::pow(q_i(2), 2) + std::pow(q_w, 2)); - q_i = (q_i/norm).eval(); - q_w = q_w/norm; - tf::Quaternion q(q_i(0), q_i(1), q_i(2), q_w); - transform.setRotation(q); - Broadcaster_.sendTransform(tf::StampedTransform(transform, _point_cloud_header.stamp, - _pub_frame, to_string(cluster_id))); - - // publish lidar tag pose - lidartag_msgs::LiDARTagDetection lidartag_msg; //single message - lidartag_msg.id = cluster_id; - lidartag_msg.size = _payload_size; - geometry_msgs::Quaternion geo_q; - geo_q.x = q_i(0); - geo_q.y = q_i(1); - geo_q.z = q_i(2); - geo_q.w = q_w; - // cout << "R: \n" << pose.rotation << endl; - // cout << "det(R): \n" << pose.rotation.determinant() << endl; - // cout << "q: " << q_i(0) << ", " - // << q_i(1) << ", " - // << q_i(2) << ", " - // << q_w << endl; - lidartag_msg.pose.position.x = Ave.x; - lidartag_msg.pose.position.y = Ave.y; - lidartag_msg.pose.position.z = Ave.z; - lidartag_msg.pose.orientation = geo_q; - lidartag_msg.header = _point_cloud_header; - lidartag_msg.header.frame_id = std::string("lidartag_") + to_string(cluster_id); - _lidartag_pose_array.header = _point_cloud_header; - _lidartag_pose_array.detections.push_back(lidartag_msg); - // cout << "R.T*NV: " << endl << pose.rotation.transpose()*NormalVec << endl; - // cout << "H: " << endl << pose.homogeneous << endl; - */ - } - - - - /* - * A function to extract the payload points from a valid cluster. - * Let's say we have 10 points on the left boundary (line) of the tag and 9 points on the right boundary - * (line) of the tag. - * It is seperated into two parts. - * TODO: should use medium instead of max points - * (i) Find the max points that we have on a ring in this cluster by - * exmaming the average points on the first 1/2 rings int((10+9)/4) - * (ii) For another half of the rings, we just find the start index and add the - * average number of points to the payload points - */ - void LiDARTag::_extractPayloadWOThreshold(ClusterFamily_t &Cluster){ - int LastRoundLength = 0; // Save to recover a missing ring - PointXYZRI average{0,0,0,0}; - for(int Ring=0; Ring<_beam_num; ++Ring){ - - // if (Cluster.payload_right_boundary_ptr[Ring]!=0) - // Cluster.payload_boundary_ptr.push_back(Cluster.payload_right_boundary_ptr[Ring]); - - // if (Cluster.payload_left_boundary_ptr[Ring]!=0) - // Cluster.payload_boundary_ptr.push_back(Cluster.payload_left_boundary_ptr[Ring]); - - if (Cluster.payload_right_boundary_ptr[Ring]==0 && - Cluster.payload_left_boundary_ptr[Ring]==0) continue; - // cout << "Ring" << Ring << endl; - else if (Cluster.payload_right_boundary_ptr[Ring]!=0 && - Cluster.payload_left_boundary_ptr[Ring]!=0){ - Cluster.payload_boundary_ptr.push_back(Cluster.payload_right_boundary_ptr[Ring]); - Cluster.payload_boundary_ptr.push_back(Cluster.payload_left_boundary_ptr[Ring]); - int StartIndex = Cluster.payload_left_boundary_ptr[Ring]->index; - int EndIndex = Cluster.payload_right_boundary_ptr[Ring]->index; - LastRoundLength = EndIndex - StartIndex; - - - for (int j=0; jindex == StartIndex){ - // Remove index itself because itself is not the part of a - // payload - for (int k=j+1; k=Cluster.ordered_points_ptr[Ring].size()) break; // make sure the index is valid - // cout << "j: " << j << endl; - // cout << "k: " << k << endl; - // cout << "validation1: " << endl; - // utils::COUT(Cluster.ordered_points_ptr[Ring][k]->point); - // - Cluster.payload.push_back(Cluster.ordered_points_ptr[Ring][k]); - average.x += Cluster.ordered_points_ptr[Ring][k]->point.x; - average.y += Cluster.ordered_points_ptr[Ring][k]->point.y; - average.z += Cluster.ordered_points_ptr[Ring][k]->point.z; - } - break; - } - } - } - Cluster.average.x = average.x/ Cluster.payload.size(); - Cluster.average.y = average.y/ Cluster.payload.size(); - Cluster.average.z = average.z/ Cluster.payload.size(); - // else if (LastRoundLength!=0 && Cluster.payload_right_boundary_ptr[Ring]!=0){ - // int EndIndex = Cluster.payload_right_boundary_ptr[Ring]->index; - - // for (int j=Cluster.ordered_points_ptr[Ring].size()-1; j>0; --j){ - // if (Cluster.ordered_points_ptr[Ring][j]->index == EndIndex){ - // Cluster.payload.push_back(Cluster.ordered_points_ptr[Ring][j]); - - // for (int k=j-1; k>j-LastRoundLength; --k){ - // if (k<0) break; // make sure the index is valid - // Cluster.payload.push_back(Cluster.ordered_points_ptr[Ring][k]); - // } - // break; - // } - // } - - // } - // else if (LastRoundLength!=0 && Cluster.payload_left_boundary_ptr[Ring]!=0){ - // int StartIndex = Cluster.payload_left_boundary_ptr[Ring]->index; - - // for (int j=0; jindex == StartIndex){ - // Cluster.payload.push_back(Cluster.ordered_points_ptr[Ring][j]); - - // for (int k=j-1; k=Cluster.ordered_points_ptr[Ring].size()) break; // make sure the index is valid - // Cluster.payload.push_back(Cluster.ordered_points_ptr[Ring][k]); - // } - // break; - // } - // } - - // } - } - } - - - bool LiDARTag::_detectPayloadBoundries(ClusterFamily_t &Cluster){ - // return true; - bool FitOkay = false; // Meaning reject this cluster and will be removed - - // Initialization - Cluster.tag_edges.upper_ring = _beam_num; - Cluster.tag_edges.lower_ring = 0; - double AverageIntensity = ((Cluster.max_intensity.intensity + - Cluster.min_intensity.intensity)/2); - double DetectionThreshold_ = (AverageIntensity - Cluster.min_intensity.intensity)/ - (_payload_intensity_threshold*Cluster.max_intensity.intensity); - //cout << "Detection Threshold: " << DetectionThreshold_ << endl; - - /* - * Compare current point's gradient intensity with next points - * gradient intensity - * Example: - * o: white, x: black - * - * a9876543210 - * ooooxxxxxxxooooo - * ^^^^ ^^^^ - * |||| |||| - * Gradient from 1-2 sould be large; the same as the gradient from 0-2 - * Gradient from 9-8 sould be large; the same as the gradient from a-8 - */ - int BoundaryPointCount = 0; // Check there're sufficient points - float RightMin = 1000; - float RightMax = -1000; - float LeftMin = 1000; - float LeftMax = -1000; - PointXYZRI PTOP; - PointXYZRI PDown; - PointXYZRI PLeft; - PointXYZRI PRight; - for (int Ring=0; Ring<_beam_num; ++Ring){ - // skip this ring if doesn't exist - if (Cluster.ordered_points_ptr[Ring].size()floor((Cluster.ordered_points_ptr[Ring].size()-2)/2); - //P>1; - --P){ - /* - * (1) By knowing it from white to black on the left calucate the - * intensity gradient - * (2) Since have thresholded already, we * could also choose > 255 - */ - // cout << "p intensity: " << Cluster.ordered_points_ptr[Ring][P]->point.intensity << endl; - // cout << "PR: " << P << endl; - // cout << "PointR: " << Cluster.ordered_points_ptr[Ring][P]->index << endl; - // utils::COUT(Cluster.ordered_points_ptr[Ring][P]->point); - // Cluster.payload_right_boundary_ptr[Ring] = Cluster.ordered_points_ptr[Ring][P]; - // FitOkay = true; - // break; - if ((Cluster.ordered_points_ptr[Ring][P]->point.intensity - - Cluster.ordered_points_ptr[Ring][P-1]->point.intensity>DetectionThreshold_) && - (Cluster.ordered_points_ptr[Ring][P+1]->point.intensity - - Cluster.ordered_points_ptr[Ring][P-1]->point.intensity>DetectionThreshold_)) { - - Cluster.payload_right_boundary_ptr[Ring] = Cluster.ordered_points_ptr[Ring][P]; - RightMin = (RightMin < Cluster.ordered_points_ptr[Ring][P]->point.y) ? RightMin : Cluster.ordered_points_ptr[Ring][P]->point.y; - RightMax = (RightMax > Cluster.ordered_points_ptr[Ring][P]->point.y) ? RightMax : Cluster.ordered_points_ptr[Ring][P]->point.y; - BoundaryPointCount ++; - - break; - } - } - - - /* [Left] - * Find edges from the left of a ring - * Start from 1 becasue we take another point on the left into account - * size -1 because we compare with next point - */ - // for (int P=2; P 255 - * (3) To determin if p if the edge: - * 1. compare with p+1 (to its right) - */ - //cout << "PL: " << P << endl; - //Cluster.payload_left_boundary_ptr[Ring] = Cluster.ordered_points_ptr[Ring][P]; - //cout << "PointL: " << Cluster.ordered_points_ptr[Ring][P]->index << endl; - //// utils::COUT(Cluster.ordered_points_ptr[Ring][P]->point); - //FitOkay = true; - - //break; - if ((Cluster.ordered_points_ptr[Ring][P]->point.intensity - - Cluster.ordered_points_ptr[Ring][P+1]->point.intensity>DetectionThreshold_) && - (Cluster.ordered_points_ptr[Ring][P-1]->point.intensity - - Cluster.ordered_points_ptr[Ring][P+1]->point.intensity>DetectionThreshold_)) { - - Cluster.payload_left_boundary_ptr[Ring] = Cluster.ordered_points_ptr[Ring][P]; - LeftMin = (LeftMin < Cluster.ordered_points_ptr[Ring][P]->point.y) ? LeftMin : Cluster.ordered_points_ptr[Ring][P]->point.y; - LeftMax = (LeftMax > Cluster.ordered_points_ptr[Ring][P]->point.y) ? LeftMax : Cluster.ordered_points_ptr[Ring][P]->point.y; - BoundaryPointCount ++; - - break; - } - } - } - - // reject if points are too less (can't even get decoded!) - if (BoundaryPointCount < int(sqrt(_tag_family))*2) { - _result_statistics.cluster_removal.boundary_point_check++; - // _debug_cluster.BoundaryPoint.push_back(&Cluster); - return false; - } else FitOkay = true; - - if (!FitOkay) { - _result_statistics.cluster_removal.no_edge_check++; - // _debug_cluster.NoEdge.push_back(&Cluster); - } - - return FitOkay; - } - - - - - - /* [Normal vector] - * A function to estimate the normal vector of a potential payload - */ - Eigen::MatrixXf - LiDARTag::_estimateNormalVector(ClusterFamily_t &Cluster){ - Eigen::MatrixXf EigenPC(3, Cluster.payload.size()); - - for (int i=0; ipoint.x - Cluster.average.x; - EigenPC(1,i) = Cluster.payload[i]->point.y - Cluster.average.y; - EigenPC(2,i) = Cluster.payload[i]->point.z - Cluster.average.z; - } - - Eigen::JacobiSVD svd(EigenPC, Eigen::ComputeFullU); - Eigen::Matrix normal_vector_robot = svd.matrixU().col(2); // Take the last column of U in SVD - - // flip through xy plane - // Eigen::Matrix3f m; - // m << 0, 1, 0, - // 0, 0, 1, - // 1, 0, 0; - - // m << 0,1,0, - // 1,0,0, - // 0,0,1; - - // m << 0,0,1, - // 1,0,0, - // 0,1,0; - // m << 0,0,1, - // 0,1,0, - // 1,0,0; - - // m << 1,0,0, - // 0,0,1, - // 0,1,0; - // cout << "Normal Vector1: \n" << normal_vector_robot << endl; - // normal_vector_robot = (m*normal_vector_robot).eval(); - // cout << "Normal Vector2: \n" << normal_vector_robot << endl; - - // Make sure consistency - if (normal_vector_robot(0)>=0) normal_vector_robot = (-normal_vector_robot).eval(); - // cout << "Normal Vector3: \n" << normal_vector_robot << endl; - - // Coordinate transform - // Eigen::Matrix normal_vector_tag; - // normal_vector_tag << normal_vector_robot(2), normal_vector_robot(0), normal_vector_robot(1); - // normal_vector_tag << normal_vector_robot(0), normal_vector_robot(2), normal_vector_robot(1); - - - return normal_vector_robot; - - // pcl::PointCloud::Ptr Cloud (new pcl::PointCloud); - - // for (int i=0; ipoint.x, - // Cluster.payload[i]->point.y, - // Cluster.payload[i]->point.z}; - // cout << "point: " << point << endl; - // Cloud->push_back(point); - // } - // pcl::PointCloud::Ptr normals (new pcl::PointCloud); - - // // pcl::IntegralImageNormalEstimation ne; - // // ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT); - // // ne.setMaxDepthChangeFactor(0.02f); - // // ne.setNormalSmoothingSize(10.0f); - // // ne.setInputCloud(Cloud); - // // ne.compute(*normals); - // // cout << "NV: " << *normals << endl; - - // pcl::NormalEstimation NE; - // NE.setInputCloud (Cloud); - // pcl::search::KdTree::Ptr tree (new pcl::search::KdTree ()); - // NE.setSearchMethod (tree); - - // // Output datasets - // pcl::PointCloud::Ptr CloudNormals (new pcl::PointCloud); - // NE.setRadiusSearch (1); - // NE.compute (*CloudNormals); - // cout << "normals: " << *CloudNormals << endl; - // std::cout << "cloud_normals->points.size (): " << CloudNormals->points.size () << std::endl; - // - // return CloudNormals; - } - - /* - * A function of ros spin - * reason: in order to put it into background as well as able to run other tasks - */ - void LiDARTag::_rosSpin(){ - while (ros::ok() && !_stop){ - ros::spinOnce(); - } - } - - - /* - * A function to cluster a single point into a new cluster or an existing cluster - */ - void LiDARTag::_clusterClassifier(const LiDARPoints_t &point, vector &ClusterBuff){ - // The first time to cluster the point cloud - int ValidCluster = 1; // Marker every cluster is valid and will be checked again later - if (ClusterBuff.size()==0){ - PointXYZRI top_most_point = point.point; - top_most_point.z = top_most_point.z + _threshold; - PointXYZRI bottom_most_point = point.point; - bottom_most_point.z -= _threshold; - - PointXYZRI front_most_point = point.point; - front_most_point.x += _threshold; - PointXYZRI back_most_point = point.point; - back_most_point.x -= _threshold; - - PointXYZRI right_most_point = point.point; - right_most_point.y -= _threshold; - PointXYZRI left_most_point = point.point; - left_most_point.y += _threshold; - //cout << "_threshold:" << _threshold << endl; - // - //cout << "\033[1;31m============== \033[0m\n"; - //cout << "First created" << endl; - //cout << "TopMost: " << top_most_point.x << ", " << top_most_point.y << ", " << top_most_point.z << endl; - //cout << "bottom_most_point: " << bottom_most_point.x << ", " << bottom_most_point.y << ", " << bottom_most_point.z << endl; - //cout << "Front: " << front_most_point.x << ", " << front_most_point.y << ", " << front_most_point.z << endl; - //cout << "back: " << back_most_point.x << ", " << back_most_point.y << ", " << back_most_point.z << endl; - //cout << "Right: " << right_most_point.x << ", " << right_most_point.y << ", " << right_most_point.z << endl; - //cout << "Left: " << left_most_point.x << ", " << left_most_point.y << ", " << left_most_point.z << endl; - - ClusterFamily_t CurrentCluster = {0, ValidCluster, top_most_point, bottom_most_point, - front_most_point, back_most_point, - right_most_point, left_most_point, - point.point}; - MaxMin_t InitialValue = {(int)1e8, 0, -1}; - CurrentCluster.max_min_index_of_each_ring.resize(_beam_num, InitialValue); - CurrentCluster.max_min_index_of_each_ring[point.point.ring].max = point.index; - CurrentCluster.max_min_index_of_each_ring[point.point.ring].min = point.index; - - CurrentCluster.max_intensity = point.point; - CurrentCluster.min_intensity = point.point; - - CurrentCluster.data.push_back(point); - ClusterBuff.push_back(CurrentCluster); - return ; - } - else { - // Take a point to go through all the existing cluster to see if this - // point belongs to any of them - // Once it is found belonging to one of the clusters then return. - // After looping though and couldn't find a belonging group then add it - // to a new cluster - TestCluster_t *new_cluster = new TestCluster_t{0}; - //cout << "\033[1;31m============== \033[0m\n"; - //cout << "ClusterBuff size: " << ClusterBuff.size() << endl; - for (int i=0; iflag)) { - delete new_cluster; - return; - } - } - // Add a new cluster - if (new_cluster->flag){ - //cout << "new cluster added" << endl; - int Newcluster_id = ClusterBuff.size(); - PointXYZRI top_most_point = point.point; - top_most_point.z += _threshold; - PointXYZRI bottom_most_point = point.point; - bottom_most_point.z -= _threshold; - - PointXYZRI front_most_point = point.point; - front_most_point.x += _threshold; - PointXYZRI back_most_point = point.point; - back_most_point.x -= _threshold; - - PointXYZRI right_most_point = point.point; - right_most_point.y -= _threshold; - PointXYZRI left_most_point = point.point; - left_most_point.y += _threshold; - - //cout << "TopMost: " << top_most_point.x << ", " << top_most_point.y << ", " << top_most_point.z << endl; - //cout << "bottom_most_point: " << bottom_most_point.x << ", " << bottom_most_point.y << ", " << bottom_most_point.z << endl; - //cout << "Front: " << front_most_point.x << ", " << front_most_point.y << ", " << front_most_point.z << endl; - //cout << "back: " << back_most_point.x << ", " << back_most_point.y << ", " << back_most_point.z << endl; - //cout << "Right: " << right_most_point.x << ", " << right_most_point.y << ", " << right_most_point.z << endl; - //cout << "Left: " << left_most_point.x << ", " << left_most_point.y << ", " << left_most_point.z << endl; - - - // Check every time when new marker added - // visualization_msgs::MarkerArray CheckArray; - // visualization_msgs::Marker CheckMarker; - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check0", - // 1, 0, 0, - // top_most_point, 0, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check1", - // 1, 0, 0, - // bottom_most_point, 1, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check2", - // 1, 0, 0, - // front_most_point, 2, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check3", - // 1, 0, 0, - // back_most_point, 3, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check4", - // 1, 0, 0, - // left_most_point, 4, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, - // "Check5", - // 1, 0, 0, - // right_most_point, 5, 0.05); - // CheckArray.markers.push_back(CheckMarker); - - // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::SPHERE, - // "Check6", - // 0, 1, 0, - // Point, 5, 0.1); - // CheckArray.markers.push_back(CheckMarker); - - // _boundary_marker_pub.publish(CheckArray); - //utils::pressEnterToContinue(); - - - new_cluster->new_cluster = {Newcluster_id, ValidCluster, top_most_point, bottom_most_point, - front_most_point, back_most_point, - right_most_point, left_most_point, - point.point}; - - // To fill in points between initial points and end points later - MaxMin_t InitialValue = {(int)1e8, 0, -1}; - new_cluster->new_cluster.max_min_index_of_each_ring.resize(_beam_num, InitialValue); - new_cluster->new_cluster.max_min_index_of_each_ring[point.point.ring].max = point.index; - new_cluster->new_cluster.max_min_index_of_each_ring[point.point.ring].min = point.index; - - new_cluster->new_cluster.max_intensity = point.point; - new_cluster->new_cluster.min_intensity = point.point; - - new_cluster->new_cluster.data.push_back(point); - ClusterBuff.push_back(new_cluster->new_cluster); - } - delete new_cluster; - } - } - - - /* - * A function update some information about a cluster if this point belongs to - * this cluster; if not belonging to this cluster then return and create a new - * one - */ - void LiDARTag::_updateCluster(const LiDARPoints_t &point, ClusterFamily_t &OldCluster, TestCluster_t *new_cluster){ - // This point is outside of the current cluster - if (!( - (point.point.z < OldCluster.top_most_point.z + _threshold) && - (point.point.x < OldCluster.front_most_point.x + _threshold) && - (point.point.y < OldCluster.left_most_point.y + _threshold) && - (OldCluster.back_most_point.x - _threshold< point.point.x) && - (OldCluster.right_most_point.y - _threshold< point.point.y) && - (OldCluster.bottom_most_point.z - _threshold< point.point.z))){ - - // cout << "\033[1;31m============== \033[0m\n"; - // cout << "New flag" << endl; - // cout << "point: " << point.point.x << ", " << point.point.y << ", " << point.point.z << endl; - // cout << "TOP.z: " << OldCluster.top_most_point.z << ", " << point.point.z << endl; - // cout << "Front.x: " << OldCluster.front_most_point.x << ", " << point.point.x << endl; - // cout << "Left.y: " << OldCluster.left_most_point.y << ", " << point.point.y << endl; - // cout << "Right.y: " << OldCluster.right_most_point.y << ", " << point.point.y << endl; - // cout << "Bottom.z: " << OldCluster.bottom_most_point.z << ", " << point.point.z << endl; - // cout << "Back.x: " << OldCluster.back_most_point.x << ", " << point.point.x << endl; - // utils::pressEnterToContinue(); - new_cluster->flag = 1; - return ; - } - else{ - new_cluster->flag = 0; - } - - // This point is inside this cluster - if (!new_cluster->flag){ - // update the boundary of the old cluster - if (point.point.x + _threshold > OldCluster.front_most_point.x) { - OldCluster.front_most_point = point.point; - OldCluster.front_most_point.x += _threshold; - } - if (point.point.x - _threshold < OldCluster.back_most_point.x) { - OldCluster.back_most_point = point.point; - OldCluster.back_most_point.x -= _threshold; - } - - if (point.point.y + _threshold > OldCluster.left_most_point.y) { - OldCluster.left_most_point = point.point; - OldCluster.left_most_point.y += _threshold; - } - if (point.point.y - _threshold< OldCluster.right_most_point.y) { - OldCluster.right_most_point = point.point; - OldCluster.right_most_point.y -= _threshold; - } - - if (point.point.z + _threshold > OldCluster.top_most_point.z) { - OldCluster.top_most_point = point.point; - OldCluster.top_most_point.z += _threshold; - } - if (point.point.z - _threshold < OldCluster.bottom_most_point.z) { - OldCluster.bottom_most_point = point.point; - OldCluster.bottom_most_point.z -= _threshold; - } - - // update the average // spend around 5-6 HZ - OldCluster.average.getVector3fMap() = ((OldCluster.average.getVector3fMap() * OldCluster.data.size() + - point.point.getVector3fMap()) / (OldCluster.data.size()+1)).eval(); - - // update the max/min index of each ring in this cluster - if (OldCluster.max_min_index_of_each_ring[point.point.ring].max < point.index) - OldCluster.max_min_index_of_each_ring[point.point.ring].max = point.index; - - if (OldCluster.max_min_index_of_each_ring[point.point.ring].min > point.index) - OldCluster.max_min_index_of_each_ring[point.point.ring].min = point.index; - - // update the max/min intensity of this cluster - if (OldCluster.max_intensity.intensity < point.point.intensity) - OldCluster.max_intensity = point.point; - - if (OldCluster.min_intensity.intensity > point.point.intensity) - OldCluster.min_intensity = point.point; - - OldCluster.data.push_back(point); - } - } - - - - - /* - * A function to transform from a customized type (LiDARpoints_t) of vector of vector (EdgeBuff) - * into a standard type (PointXYZRI) of pcl vector (out) - */ - void LiDARTag::_buffToPclVector(const std::vector> &EdgeBuff, - pcl::PointCloud::Ptr Out){ - for (int RingNumber=0; RingNumber<_beam_num; ++RingNumber){ - if (EdgeBuff.at(RingNumber).size()!=0){ - for (int i=0; ipush_back(EdgeBuff[RingNumber][i].point); - } - } - } - } - - - /* - * A function to prepare for displaying results in rviz - */ - void LiDARTag::_clusterToPclVectorAndMarkerPublisher(const std::vector &Cluster, - pcl::PointCloud::Ptr OutCluster, - pcl::PointCloud::Ptr OutPayload, - visualization_msgs::MarkerArray &ClusterArray){ - - /* initialize random seed for coloring the marker*/ - srand (time(NULL)); - visualization_msgs::MarkerArray BoundMarkArray; - visualization_msgs::MarkerArray PayloadMarkArray; - - - int PointsInClusters = 0; - for (int Key=0; Key0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - /* - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector1" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector2" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector3" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector4" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector5" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector6" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - - LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, - "NormalVector7" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - Cluster[Key].average, 1, 0.01); - BoundaryMarker.scale.x = 0.15; - // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? - // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); - BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); - BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); - BoundaryMarker.pose.orientation.w = 0; - BoundMarkArray.markers.push_back(BoundaryMarker); - */ - - - - // LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::SPHERE, - // "Average" + to_string(Cluster[Key].cluster_id), - // r, g, b, - // Cluster[Key].average, 5, 0.04); - // BoundMarkArray.markers.push_back(BoundaryMarker); - - - - //_cluster_pub.publish(BoundaryMarkerList); - //LiDARTag::_assignLine(BoundaryMarkerList, visualization_msgs::Marker::LINE_STRIP, - // r, g, b, - // Cluster[Key], 1); - //_cluster_pub.publish(BoundaryMarkerList); - - // _boundary_marker_pub.publish(BoundMarkArray); - - // Draw payload boundary marker - visualization_msgs::Marker PayloadMarker; - - if (_adaptive_thresholding){ - // Upper boundary - for (int i=0; ipoint, i, 0.015); - PayloadMarkArray.markers.push_back(PayloadMarker); - } - - // Lower boundary - for (int i=0; ipoint, i, 0.015); - PayloadMarkArray.markers.push_back(PayloadMarker); - } - - // Left boundary (green) - for (int i=0; ipoint, i, 0.015); - PayloadMarkArray.markers.push_back(PayloadMarker); - } - - // Right boundary (red) - for (int i=0; ipoint, i, 0.015); - PayloadMarkArray.markers.push_back(PayloadMarker); - } - } - else { - - // cout << "size1: " << Cluster[Key].payload_boundary_ptr.size() << endl; - int count = 0; - for (int i=0; ipoint, count, 0.015); - // PayloadMarkArray.markers.push_back(PayloadMarker); - // count ++; - - // LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::SPHERE, - // "PayloadBoundary_" + to_string(Cluster[Key].cluster_id), - // 1, 0, 0, - // Cluster[Key].payload_boundary_ptr[i][1]->point, count, 0.015); - // count ++; - // PayloadMarkArray.markers.push_back(PayloadMarker); - // } - // for (int k=0; kpoint, i, 0.015); - PayloadMarkArray.markers.push_back(PayloadMarker); - count ++; - // } - } - } - - // Text - /* - LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::TEXT_VIEW_FACING, - "PayloadUpperBoundary_text_" + to_string(Cluster[Key].cluster_id), - 1, 1, 1, - Cluster[Key].tag_edges.upper_line[0]->point, 5, 0.05, - string("Ring: " + to_string(Cluster[Key].tag_edges.upper_line[0]->point.ring)) - ); - PayloadMarkArray.markers.push_back(PayloadMarker); - - LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::TEXT_VIEW_FACING, - "PayloadLowerBoundary_text_" + to_string(Cluster[Key].cluster_id), - 1, 1, 1, - Cluster[Key].tag_edges.lower_line[0]->point, 5, 0.05, - string("Ring: " + to_string(Cluster[Key].tag_edges.lower_line[0]->point.ring)) - ); - PayloadMarkArray.markers.push_back(PayloadMarker); - */ - - - // corner points and RANSAC line - if (_adaptive_thresholding){ - Eigen::Vector4f EigenPoint; - PointXYZRI point; // just for conversion - - for (int i=0; i<4; ++i){ // 4 corners - // Corners - if (i!=3){ - pcl::lineWithLineIntersection(Cluster[Key].line_coeff[i], Cluster[Key].line_coeff[i+1], - EigenPoint, 1e-2); - } - else { - pcl::lineWithLineIntersection(Cluster[Key].line_coeff[i], Cluster[Key].line_coeff[0], - EigenPoint, 1e-2); - } - - LiDARTag::_eigenVectorToPointXYZRI(EigenPoint, point); - LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::SPHERE, - "Corner_" + to_string(Cluster[Key].cluster_id), - 0, 1, 1, - point, i, 0.02); - PayloadMarkArray.markers.push_back(PayloadMarker); - - // RANSAC - LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::ARROW, - "RANSAC" + to_string(Cluster[Key].cluster_id), - 1, 1, 0, - point, i, 0.01); - double Length = sqrt(pow(Cluster[Key].line_coeff[i][3],2) + - pow(Cluster[Key].line_coeff[i][4],2) + - pow(Cluster[Key].line_coeff[i][5],2)); - PayloadMarker.scale.x = 0.15; - PayloadMarker.pose.orientation.x = Cluster[Key].line_coeff[i][3]/Length; - PayloadMarker.pose.orientation.y = Cluster[Key].line_coeff[i][4]/Length; - PayloadMarker.pose.orientation.z = Cluster[Key].line_coeff[i][5]/Length; - PayloadMarkArray.markers.push_back(PayloadMarker); - } - } - - // Add lines to the tag - //LiDARTag::_assignLine(PayloadMarker, PayloadMarkArray, - // visualization_msgs::Marker::LINE_STRIP, - // "left_line_" + to_string(Cluster[Key].cluster_id), - // r, g, b, - // PointTL, PointTR, 1); - //PayloadMarkArray.markers.push_back(PayloadMarker); - - - // Draw all detected-filled cluster points - for (int i=0; ipush_back(Cluster[Key].data[i].point); - double Intensity = Cluster[Key].data[i].point.intensity; - LiDARTag::_assignMarker(Marker, visualization_msgs::Marker::SPHERE, - to_string(Cluster[Key].cluster_id), - Intensity, Intensity, Intensity, - Cluster[Key].data[i].point, i, 0.01); - ClusterArray.markers.push_back(Marker); - } - - // Add all payload points to a vector and will be publish to another - // channel for both visualizatoin and creating training datasets - // cout << "payload size2: " << Cluster[Key].payload.size() << endl; - for (int i=0; ipush_back(Cluster[Key].payload[i]->point); - // cout << "Intensity: " << Cluster[Key].payload[i]->point.intensity << endl; - } - - - } - if (PointsInClusters>_filling_max_points_threshold) { - cout << "Too many points on a tag" << endl; - exit(-1); - } - - //cout << "BoundaryMarkerList size/10: " << BoundaryMarkerList.points.size()/10 << endl; - _boundary_marker_pub.publish(BoundMarkArray); - _cluster_marker_pub.publish(ClusterArray); - _payload_marker_pub.publish(PayloadMarkArray); - } - - - /* - * A function to draw a line between two points - */ - void LiDARTag::_assignLine(visualization_msgs::Marker &Marker, visualization_msgs::MarkerArray MarkArray, - const uint32_t Shape, const string ns, - const double r, const double g, const double b, - const PointXYZRI point1, const PointXYZRI point2, const int Count){ - Marker.header.frame_id = _pub_frame; - Marker.header.stamp = _current_scan_time; - //Marker.ns = string("Boundary_") + to_string(Cluster.cluster_id); - Marker.ns = ns; - Marker.id = Count; - Marker.type = Shape; - - Marker.action = visualization_msgs::Marker::ADD; - Marker.pose.orientation.x = 0.0; - Marker.pose.orientation.y = 0.0; - Marker.pose.orientation.z = 0.0; - Marker.pose.orientation.w = 1.0; - - // Set the scale of the marker -- 1x1x1 here means 1m on a side - Marker.scale.x = 1; - - // Set the color -- be sure to set alpha to something non-zero! - Marker.color.r = r; - Marker.color.g = g; - Marker.color.b = b; - Marker.color.a = 1.0; - - geometry_msgs::Point p; - p.x = point1.x; - p.y = point1.y; - p.z = point1.z; - Marker.points.push_back(p); - p.x = point2.x; - p.y = point2.y; - p.z = point2.z; - Marker.points.push_back(p); - MarkArray.markers.push_back(Marker); - } - - - /* - * A function to draw a point in rviz - */ - void LiDARTag::_assignMarker(visualization_msgs::Marker &Marker, const uint32_t Shape, const string NameSpace, - const double r, const double g, const double b, - const PointXYZRI &point, - const int Count, const double Size, const string Text){ - Marker.header.frame_id = _pub_frame; - Marker.header.stamp = _current_scan_time; - Marker.ns = NameSpace; - Marker.id = Count; - Marker.type = Shape; - Marker.action = visualization_msgs::Marker::ADD; - Marker.pose.position.x = point.x; - Marker.pose.position.y = point.y; - Marker.pose.position.z = point.z; - Marker.pose.orientation.x = 0.0; - Marker.pose.orientation.y = 0.0; - Marker.pose.orientation.z = 0.0; - Marker.pose.orientation.w = 1.0; - Marker.text = Text; - Marker.lifetime = ros::Duration(_sleep_time_for_vis); // should disappear along with updateing rate - - // Set the scale of the marker -- 1x1x1 here means 1m on a side - Marker.scale.x = Size; - Marker.scale.y = Size; - Marker.scale.z = Size; - - // Set the color -- be sure to set alpha to something non-zero! - Marker.color.r = r; - Marker.color.g = g; - Marker.color.b = b; - Marker.color.a = 1.0; - } - - - /* - * A valid cluster, valid tag, the points from the original point cloud that belong to the cluster - * could be estimated from the LiDAR system - * Therefore, if the points on the tag is too less, which means it is not a valid - * tag where it might just a shadow of a valid tag - */ - bool LiDARTag::_clusterPointsCheck(ClusterFamily_t &Cluster){ - int points = LiDARTag::_areaPoints(Cluster.average.x, _payload_size, _payload_size); - //cout << "points: " << points << endl; - //cout << "Data: " << Cluster.data.size() << endl; - // return true; - if (Cluster.data.size() < floor(points/ _points_threshold_factor)) return false; - else return true; - } - - - /* - * A function to transform an eigen type of vector to pcl point type - */ - void LiDARTag::_eigenVectorToPointXYZRI(const Eigen::Vector4f &Vector, PointXYZRI &point){ - point.x = Vector[0]; - point.y = Vector[1]; - point.z = Vector[2]; - } - - - void LiDARTag::_getCodeNaive(string &Code, pcl::PointCloud payload){ - int topring = 0; - int bottomring = _beam_num; - PointXYZRI tl= payload[0]->point; - PointXYZRI tr= payload[0]->point; - PointXYZRI br= payload[0]->point; - PointXYZRI bl= payload[0]->point; - - - // Find the size of the payload - for (int i=0; ipoint; - if (point.y>tl.y && point.z>tl.z) tl = point; - if (point.y>bl.y && point.ztr.z) tr = point; - if (point.y payload49(_tag_family, 0); - int d = sqrt(_tag_family); - float IntervalY = abs( (tl.y+bl.y)/2 - (tr.y+br.y)/2 ) /(d+_black_border-1); - float IntervalZ = abs( (tl.z+tr.z)/2 - (bl.z+br.z)/2 ) /(d+_black_border-1); - - - if (_fake_tag){ - tl.y = 0; - tl.z = 0; - IntervalY = 1; - IntervalZ = 1; - payload.clear(); - payload.reserve((_tag_family+4*d*_black_border+4*(std::pow(_black_border, 2)))); - float j = 0; - float k = 0; - LiDARPoints_t point; - for (int i=0; i<(_tag_family+4*d*_black_border+4*(std::pow(_black_border, 2))); ++i){ - if (i%(d+2*_black_border)==0 && i!=0) {k++; j=0;} - LiDARPoints_t *point = new LiDARPoints_t{{0, j, k,0,0}, 0,0,0,0}; - payload.push_back(point); - // cout << "j,k: " << j << ", " << k << endl; - j++; - //cout << "payload[i]" << payload[i]->point.y << ", " << payload[i]->point.z << endl; - // delete point; - } - payload[20]->point.intensity = 100; - payload[26]->point.intensity = 100; - payload[27]->point.intensity = 100; - payload[28]->point.intensity = 100; - payload[34]->point.intensity = 100; - payload[36]->point.intensity = 100; - payload[43]->point.intensity = 100; - payload[45]->point.intensity = 100; - } - - - // Calcutate Average intensity for thresholding - float AveIntensity = 0; - for (int i=0; ipoint.intensity; - } - AveIntensity /= payload.size(); - // cout << "size: " << payload.size() << endl; - // cout << "AveIntensity: " << AveIntensity << endl; - - - // Split into grids - for (int i=0; ipoint); - // cout << "i: " << i << endl; - // cout << "point.y: " << pointPtr->y << endl; - // cout << "point.z: " << pointPtr->z << endl; - float DeltaY = abs(pointPtr->y - tl.y); - float DeltaZ = abs(pointPtr->z - tl.z); - - // if (DeltaY==0 || (DeltaY)) { - // if (pointPtr->intensity < AveIntensity) payload49[0] -= 1; - // else payload49[0] += 1; - // continue; - // } - int Y = floor(DeltaY/IntervalY); - int Z = floor(DeltaZ/IntervalZ); - // cout << "Y: " << Y << endl; - // cout << "Z: " << Z << endl; - - // remove black borders - if (Y>=_black_border && Z>=_black_border && Y<=d+_black_border && Z<=d+_black_border){ - int y = (Y-_black_border)%d; // the yth column (remove the black border) - int z = (Z-_black_border)%d; // the zth row (remove the black border) - - int k = d*z + y; // index in a 1D vector - // cout << "y: " << y << endl; - // cout << "z: " << z << endl; - // cout << "k: " << k << endl; - // cout << "intensity: " << pointPtr->intensity << endl; - if (pointPtr->intensity <= AveIntensity) payload49[k] -= 1; - else payload49[k] += 1; - //cout << "payload[k]: " << payload49[k] << endl; - //cout << "--" << endl; - } - - } - - // Threshold into black and white - for (int i=0; i<_tag_family; ++i){ - if (payload49[i]<0) Code += to_string(0); - else Code += to_string(1); - } - - for (int i=0; i<_tag_family; ++i){ - if (i%d==0){ - cout << "\n"; - cout << " " << Code[i]; - } - else{ - cout << " " << Code[i]; - } - } - - - - Code += "UL"; - //cout << "\ncodeB: " << Code << endl; - //0101111111111111UL - //cout << "Code: " << "0010001100011011UL" << endl; - cout << "\nCode 1: \n" << " 0 0 1 0\n 1 1 1 0\n 1 0 1 0\n 0 1 1 1" << endl; - // exit(-1); - // Code = "0010001100011011UL"; - //Code = "0b0000011111100000011000011000110011100000111111111UL"; - // Code = "11111100000011000011000110011100000111111111UL"; //1 - //Code = "0001100111110000011001100011111000000110001100011UL"; // 2 - //cout << "codeA: " << Code << endl; - } - - - /* Decode using Weighted Gaussian weight - * return 0: normal - * return -1: not enough return - * return -2: fail corner detection - */ - int LiDARTag::_getCodeWeightedGaussian(string &Code, Homogeneous_t &pose, - int &payload_points, - const PointXYZRI &average, - const pcl::PointCloud &payload, - const std::vector &payload_boundary_ptr){ - /* p11 - * . p11. . . . . p41 ^ z - * . . . ave . y __| - * p21 . . . p41 . . . - * . . . . - * . p21. . . . . p31 - * p31 - * px2s are just second largest number corresponding to x position - */ - - // For visualization - visualization_msgs::MarkerArray GridMarkerArray; - visualization_msgs::Marker GridMarker; - - visualization_msgs::Marker LineStrip; - LineStrip.header.frame_id = _pub_frame; - LineStrip.header.stamp = _current_scan_time; - LineStrip.ns = "boundary" ; - LineStrip.action = visualization_msgs::Marker::ADD; - LineStrip.pose.orientation.w= 1.0; - LineStrip.id = 1; - LineStrip.type = visualization_msgs::Marker::LINE_STRIP; - LineStrip.scale.x = 0.002; - LineStrip.color.b = 1.0; - LineStrip.color.a = 1.0; - - - - PointXYZRI p11{0, 0, -1000, 0}; - PointXYZRI p21{0, -1000, 0, 0}; - PointXYZRI p31{0, 0, 1000, 0}; - PointXYZRI p41{0, 1000, 0, 0}; - - PointXYZRI p12{0, 0, -1000, 0}; - PointXYZRI p22{0, -1000, 0, 0}; - PointXYZRI p32{0, 0, 1000, 0}; - PointXYZRI p42{0, 1000, 0, 0}; - - - // Find the largest - for (int i=0; ipoint; - - if (point.z>=p11.z) p11 = point; - if (point.y>=p21.y) p21 = point; - if (point.z<=p31.z) p31 = point; - if (point.y<=p41.y) p41 = point; - - } - if(_grid_viz){ - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("11"), - 0, 0, 0, - p11, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("21"), - 0, 0, 0, - p21, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("31"), - 0, 0, 0, - p31, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("41"), - 0, 0, 0, - p41, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - } - - // Find the second large - for (int i=0; ipoint; - if (point.z=p12.z) p12 = point; - if (point.y=p22.y) p22 = point; - - if (point.z>p31.z && point.z<=p32.z) p32 = point; - if (point.y>p41.y && point.y<=p42.y) p42 = point; - } - - if(_grid_viz){ - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("12"), - 0, 0, 0, - p12, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("22"), - 0, 0, 0, - p22, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("32"), - 0, 0, 0, - p32, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("42"), - 0, 0, 0, - p42, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - } - - PointXYZRI p1 = utils::pointsAddDivide(p11, p12, 2); - PointXYZRI p2 = utils::pointsAddDivide(p21, p22, 2); - PointXYZRI p3 = utils::pointsAddDivide(p31, p32, 2); - PointXYZRI p4 = utils::pointsAddDivide(p41, p42, 2); - - // check condition of the detected corners - // if corners are not between certain angle or distance, - // consider the tag is up right => - // change way of detection - int status = utils::checkCorners(_payload_size, p1, p2, p3, p4); - if (status!=0){ - // the tag is up right - p1 = {0, 0,-1000, 0}; - p2 = {0, 0, 1000, 0}; - p3 = {0, 0, 1000, 0}; - p4 = {0, 0,-1000, 0}; - for (int i=0; ipoint; - - // left boundary - if (point.z>=p1.z && point.y > average.y/2) p1 = point; - if (point.z<=p2.z && point.y > average.y/2) p2 = point; - - // right boundary - if (point.z<=p3.z && point.y < average.y/2) p3 = point; - if (point.z>=p4.z && point.y < average.y/2) p4 = point; - } - } - - if(_grid_viz){ - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("1"), - 1, 1, 1, - p1, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("2"), - 1, 1, 1, - p2, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("3"), - 1, 1, 1, - p3, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Grid_" + string("4"), - 1, 1, 1, - p4, 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - GridMarkerArray.markers.push_back(GridMarker); - } - - - int d = std::sqrt(_tag_family); - Eigen:: MatrixXf Vertices = Eigen::MatrixXf::Zero(3,5); - utils::formGrid(Vertices, 0, 0, 0, _payload_size); - Eigen::Matrix3f R; - // Eigen::MatrixXf VerticesOffset = (Vertices.colwise() - utils::toEigen(average)); - // cout << "vertice: " << Vertices << endl; - // cout << "verticeOffset: " << VerticesOffset << endl; - // cout << "Average: " << utils::toEigen(average) << endl; - utils::minus(p1, average); - utils::minus(p2, average); - utils::minus(p3, average); - utils::minus(p4, average); - - utils::fitGrid(Vertices, R, p1, p2, p3, p4); - Eigen::Vector3f Angle = utils::rotationMatrixToEulerAngles(R); - - if(_grid_viz){ - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Model_" + string("1"), - 0, 1, 0, - utils::toVelodyne(Vertices.col(1)), 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Model_" + string("2"), - 0, 1, 0, - utils::toVelodyne(Vertices.col(2)), 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Model_" + string("3"), - 0, 1, 0, - utils::toVelodyne(Vertices.col(3)), 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, - "Model_" + string("4"), - 0, 1, 0, - utils::toVelodyne(Vertices.col(4)), 1, 0.01); - GridMarkerArray.markers.push_back(GridMarker); - - geometry_msgs::Point p; - p.x = Vertices(0, 1); - p.y = Vertices(1, 1); - p.z = Vertices(2, 1); - LineStrip.points.push_back(p); - p.x = Vertices(0, 2); - p.y = Vertices(1, 2); - p.z = Vertices(2, 2); - LineStrip.points.push_back(p); - p.x = Vertices(0, 3); - p.y = Vertices(1, 3); - p.z = Vertices(2, 3); - LineStrip.points.push_back(p); - p.x = Vertices(0, 4); - p.y = Vertices(1, 4); - p.z = Vertices(2, 4); - LineStrip.points.push_back(p); - p.x = Vertices(0, 1); - p.y = Vertices(1, 1); - p.z = Vertices(2, 1); - LineStrip.points.push_back(p); - } - - // Calcutate Average intensity for thresholding - float AveIntensity = 0; - for (int i=0; ipoint.intensity; - - AveIntensity /= payload.size(); - - vector Votes(payload.size()); - vector vR(std::pow((d+2*_black_border), 2)); - vector vG(std::pow((d+2*_black_border), 2)); - vector vB(std::pow((d+2*_black_border), 2)); - - // pick a random color for each cell - if(_grid_viz){ - for (int i=0; ipoint); - utils::getProjection(p1, p4, *pointPtr, t14, v14); - utils::getProjection(p1, p2, *pointPtr, t12, v12); - Votes[i].p = pointPtr; - PointXYZRI p; // for visualization - utils::assignCellIndex(_payload_size, R, p, - average, d + 2*_black_border, Votes[i]); - if(_grid_viz){ - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::SPHERE, - "TransPoints", - vR[Votes[i].cell], vG[Votes[i].cell], vB[Votes[i].cell], - p, i, 0.005); - GridMarkerArray.markers.push_back(GridMarker); - } - - } - vector> Grid(std::pow((d+2*_black_border), 2)); - utils::sortPointsToGrid(Grid, Votes); - int TooLessReturn = 0; - int PayloadPointCount = 0; - for (int i=(d+2*_black_border)*_black_border+_black_border; - i<(d+2*_black_border)*(_black_border+d)-_black_border; ++i){ - - if ((i%(d+2*_black_border)<_black_border) || - (i%(d+2*_black_border)>(d+_black_border-1))) continue; - - if (Grid[i].size() < _min_returns_per_grid) TooLessReturn ++; - if (TooLessReturn>_max_decode_hamming) return -1; - - float WeightedProb = 0; - float WeightSum = 0; - float minIntensity = 10000.; - float maxIntensity = -1.; - double r; - double g; - double b; - - // pick a random color for each cell - if(_grid_viz){ - r = (double) rand() / RAND_MAX; - g = (double) rand() / RAND_MAX; - b = (double) rand() / RAND_MAX; - } - - for (int j=0; jp), j, 0.005); - GridMarkerArray.markers.push_back(GridMarker); - LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::SPHERE, - "Center" + to_string(i), - 1, 1, 1, - Grid[i][j]->centroid, j, 0.005); - GridMarkerArray.markers.push_back(GridMarker); - LiDARTag::_assignMarker(GridMarker, - visualization_msgs::Marker::TEXT_VIEW_FACING, - "Prob" + to_string(i), - 1, 1, 1, - *(Grid[i][j]->p), j, 0.003, - to_string((Grid[i][j]->p->intensity))); - GridMarkerArray.markers.push_back(GridMarker); - } - WeightedProb += Grid[i][j]->weight*Grid[i][j]->p->intensity; - WeightSum += Grid[i][j]->weight; - } - WeightedProb /= WeightSum; - PayloadPointCount += Grid[i].size(); - - if (WeightedProb>0.5) Code += to_string(1); - else Code += to_string(0); - } - payload_points = PayloadPointCount; - - Code += "UL"; - - if(_grid_viz){ - _payload_grid_pub.publish(GridMarkerArray); - _payload_grid_line_pub.publish(LineStrip); - } - return 0; - } - - - /* [Payload decoding] - * A function to decode payload with different means - * 0: Naive decoding - * 1: Weighted Gaussian - * 2: Deep learning - * 3: Gaussian Process - * 4: ?! - */ - bool LiDARTag::_decodPayload(ClusterFamily_t &Cluster){ - string Code(""); - bool ValidTag = true; - string Msg; - - if (_decode_method==0){ // Naive decoder - LiDARTag::_getCodeNaive(Code, Cluster.payload); - } - else if (_decode_method==1){ // Weighted Gaussian - int status = LiDARTag::_getCodeWeightedGaussian( - Code, Cluster.pose, - Cluster.payload_without_boundary, // size of actual payload - Cluster.average, - Cluster.payload, - Cluster.payload_boundary_ptr); - - if (_id_decoding){ - if (status==-1){ - ValidTag = false; - _result_statistics.cluster_removal.decoder_not_return ++; - Cluster.valid = 0; - Msg = "Not enough return"; - } - else if (status==-2){ - ValidTag = false; - _result_statistics.cluster_removal.decoder_fail_corner ++; - Cluster.valid = 0; - Msg = "Fail corner detection"; - } - } - } - - if (ValidTag && _id_decoding){ - uint64_t Rcode = stoull(Code, nullptr, 2); - BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &Cluster.entry); - Cluster.cluster_id = Cluster.entry.id; - ROS_INFO_STREAM("id: " << Cluster.entry.id); - ROS_DEBUG_STREAM("hamming: " << Cluster.entry.hamming); - ROS_DEBUG_STREAM("rotation: " << Cluster.entry.rotation); - } - else { - // too big, return as an invalid tag - Code = "1111111111111111UL"; - ROS_DEBUG_STREAM("\nCODE: " << Code); - uint64_t Rcode = stoull(Code, nullptr, 2); - BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &Cluster.entry); - Cluster.cluster_id = 8888; - ROS_DEBUG_STREAM("id: " << Cluster.cluster_id); - ROS_DEBUG_STREAM("hamming: " << Cluster.entry.hamming); - ROS_DEBUG_STREAM("rotation: " << Cluster.entry.rotation); - } - return ValidTag; - } - - - - /* [Decoder] - * Create hash table of chosen tag family - */ - void LiDARTag::_initDecoder(){ - string famname = "tag" + to_string(_tag_family) + "h" + to_string(_tag_hamming_distance); - if (famname == "tag49h14") tf = tag49h14_create(); - else if (famname == "tag16h5") tf = tag16h5_create(); - else { - cout << "[ERROR]" << endl; - cout << "Unrecognized tag family name: "<< famname << ". Use e.g. \"tag16h5\". " << endl; - cout << "This is line " << __LINE__ << " of file "<< __FILE__ << - " (function " << __func__ << ")"<< endl; - exit(0); - } - tf->black_border = _black_border; - cout << "Preparing for tags: " << famname << endl; - BipedAprilLab::QuickDecodeInit(tf, _max_decode_hamming); - } - - /* - * - */ - void LiDARTag::_testInitDecoder(){ - uint64_t rcode = 0x0001f019cf1cc653UL; - QuickDecodeEntry_t entry; - BipedAprilLab::QuickDecodeCodeword(tf, rcode, &entry); - cout << "code: " << entry.rcode << endl; - cout << "id: " << entry.id << endl; - cout << "hamming: " << entry.hamming << endl; - cout << "rotation: " << entry.rotation << endl; - exit(0); - } - - - - /* [not used] [not finished] - * A function to group edges - */ - template - void LiDARTag::_freeVec(Container& c) { - while(!c.empty()) { - if (c.back()!=nullptr) { - delete c.back(); - c.back()=nullptr; - } - c.pop_back(); - } - } - - void LiDARTag::_freePCL(pcl::PointCloud &vec){ - while(!vec.empty()) delete vec.back(), vec.erase(vec.end()); - } - - void LiDARTag::_freeTagLineStruc(TagLines_t &tag_edges){ - LiDARTag::_freeVec(tag_edges.upper_line); - LiDARTag::_freeVec(tag_edges.lower_line); - LiDARTag::_freeVec(tag_edges.left_line); - LiDARTag::_freeVec(tag_edges.right_line); - - LiDARTag::_freeVec(tag_edges.bottom_left); - LiDARTag::_freeVec(tag_edges.bottom_right); - LiDARTag::_freeVec(tag_edges.top_left); - LiDARTag::_freeVec(tag_edges.top_right); - } -} // namespacer diff --git a/src/lidartag.cc b/src/lidartag.cc new file mode 100644 index 0000000..2eae394 --- /dev/null +++ b/src/lidartag.cc @@ -0,0 +1,3806 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include // SVD +#include // matrix exponential +#include // tensor output + +#include // package +#include + +#include "lidartag.h" +#include "apriltag_utils.h" +#include "utils.h" +#include "ultra_puck.h" + +#include +#include // std::sort +#include /* sqrt, pow(a,b) */ +#include /* clock_t, clock, CLOCKS_PER_SEC */ +#include +#include /* srand, rand */ +#include // log files +#include + +/* CONSTANT */ +#define SQRT2 1.41421356237 +#define MAX_INTENSITY 255 +#define MIN_INTENSITY 0 + +using namespace std; +using namespace std::chrono; + +namespace BipedLab { + LiDARTag::LiDARTag(): + _nh("~"), _point_cloud_received(0), + _pub_frame("velodyne"), // what frame of the published pointcloud should be + _stop(0), // Just a switch for exiting this program while using valgrind + _thread_vec(nullptr) { + LiDARTag::_getParameters(); + pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS); + if (_id_decoding){ + cout << "\033[1;32m\n\n===== loading tag family ===== \033[0m\n"; + LiDARTag::_initDecoder(); + } + + if (_decode_method!=0 && _decode_method!=1 && _decode_method!=2){ + ROS_ERROR("Please use 0, 1 or 2 for decode_method in the launch file"); + ROS_INFO_STREAM("currently using: "<< _decode_method); + } + cout << "\033[1;32m=========================== \033[0m\n"; + cout << "\033[1;32m=========================== \033[0m\n"; + + ROS_INFO("ALL INITIALIZED!"); + _LiDAR1_sub = + _nh.subscribe(_pointcloud_topic, 50, + &LiDARTag::_pointCloudCallback, this); + _edge_pub = + _nh.advertise("WholeEdgedPC", 10); + _transformed_points_pub = + _nh.advertise( + "TransformedPoints", 10); + _transformed_points_tag_pub = + _nh.advertise( + "TransformedPointsTag", 10); + _edge1_pub = + _nh.advertise( + "EdgeGroup1", 10); + _edge2_pub = + _nh.advertise( + "EdgeGroup2", 10); + _edge3_pub = + _nh.advertise( + "EdgeGroup3", 10); + _edge4_pub = + _nh.advertise( + "EdgeGroup4", 10); + _boundary_pub = + _nh.advertise( + "BoundaryPts", 10); + _cluster_pub = + _nh.advertise("DetectedPC", 10); + // _index_pub = + // _nh.advertise("IndexPC", 10); + _payload_pub = + _nh.advertise("Associated_pattern_3d", 10); + _payload3d_pub = + _nh.advertise("Template_points_3d", 10); + _tag_pub = + _nh.advertise("Template_points", 10); + _ini_tag_pub = + _nh.advertise("Initial_Template_points", 10); + _boundary_marker_pub = + _nh.advertise( + "BoundaryMarker", 10); + _id_marker_pub = + _nh.advertise( + "IDMarkers", 10); + _cluster_marker_pub = + _nh.advertise( + "ClusterMarker", 10); + _payload_marker_pub = + _nh.advertise( + "PayloadEdges", 10); + _payload_grid_pub = + _nh.advertise("Grid", 10); + _payload_grid_line_pub = + _nh.advertise("GridLine", 10); + _ideal_frame_pub = + _nh.advertise("IdealFrame", 10); + _tag_frame_pub = + _nh.advertise("TagFrame", 10); + _edge_vector_pub = + _nh.advertise( + "EdgeVector", 10); + _lidartag_pose_pub = + _nh.advertise( + "LiDARTagPose", 1); + _clustered_points_pub = + _nh.advertise("ClusterEdgePC", 5); + _detectionArray_pub = + _nh.advertise( + lidartag_detection_topic,10); + + // put ros spin into a background thread + boost::thread RosSpin(&LiDARTag::_rosSpin, this); + + // Eigen::Matrix3d lie_group; + // lie_group << 1, 0, 0, + // 0, 0, -1, + // 0, 1, 0; + // Eigen::Vector3d lie_algebra = utils::Log_SO3(lie_group); + // Eigen::Matrix3d lie_test_result = utils::Exp_SO3(lie_algebra); + // cout << "rotation: \n" << lie_group << endl; + // cout << "lie_algebra: \n" << lie_algebra < 0: \n" << (result.array() > 0 ) << endl; + // cout << "ans.cwisemax(0): \n" << result.array().cwiseMax(0) << endl; + // cout << "ans.cwisemax(0).sum: \n" << result.array().cwiseMax(0).rowwise().sum() << endl; + + // _LiDAR_system.angle_list.insert(10); + // _LiDAR_system.angle_list.insert(10.0049); + // _LiDAR_system.angle_list.insert(10.006); + // _LiDAR_system.angle_list.insert(10.0061); + // _LiDAR_system.angle_list.insert(11); + // _LiDAR_system.angle_list.insert(12); + // _LiDAR_system.angle_list.insert(11); + // cout << "Elements of set in sorted order: \n"; + // for (auto it : _LiDAR_system.angle_list) + // cout << it << " "; + + // cout << endl; + + // Eigen::MatrixXf convex_hull; + // Eigen::MatrixXf P(Eigen::MatrixXf::Random(4, 100)); + // utils::constructConvexHull(P, convex_hull); + // std::cout << "area: " << utils::computePolygonArea(convex_hull) << std::endl; + + // exit(0); + + + ROS_INFO("Waiting for pointcloud data"); + LiDARTag::_waitForPC(); + + // Exam the minimum distance of each point in a ring + ROS_INFO("Analyzing system"); + LiDARTag::_analyzeLiDARDevice(); + boost::thread ExtractionSpin(&LiDARTag::_mainLoop, this); + ExtractionSpin.join(); + RosSpin.join(); + } + + /* + * Main loop + */ + void LiDARTag::_mainLoop(){ + ROS_INFO("Start points of interest extraction"); + // ROS_INFO_STREAM("Tag_size:" << _payload_size); + //ros::Rate r(10); // 10 hz + ros::Duration duration(_sleep_time_for_vis); + clock_t StartAve = clock(); + pcl::PointCloud::Ptr clusterpc( + new pcl::PointCloud); + pcl::PointCloud::Ptr clusteredgepc( + new pcl::PointCloud); + pcl::PointCloud::Ptr payloadpc( + new pcl::PointCloud); + // pcl::PointCloud::Ptr indexpc( + // new pcl::PointCloud); + pcl::PointCloud::Ptr boundarypc( + new pcl::PointCloud); + pcl::PointCloud::Ptr tagpc( + new pcl::PointCloud); + pcl::PointCloud::Ptr ini_tagpc( + new pcl::PointCloud); + pcl::PointCloud::Ptr payload3dpc( + new pcl::PointCloud); + pcl::PointCloud::Ptr edge_group1( + new pcl::PointCloud); + pcl::PointCloud::Ptr edge_group2( + new pcl::PointCloud); + pcl::PointCloud::Ptr edge_group3( + new pcl::PointCloud); + pcl::PointCloud::Ptr edge_group4( + new pcl::PointCloud); + clusterpc->reserve(_point_cloud_size); + clusteredgepc->reserve(_point_cloud_size); + // indexpc->reserve(_point_cloud_size); + tagpc->reserve(_point_cloud_size); + ini_tagpc->reserve(_point_cloud_size); + edge_group1->reserve(_point_cloud_size); + edge_group2->reserve(_point_cloud_size); + edge_group3->reserve(_point_cloud_size); + edge_group4->reserve(_point_cloud_size); + // XXX Tunalbe + payloadpc->reserve(_point_cloud_size); + payload3dpc->reserve(_point_cloud_size); + boundarypc->reserve(_point_cloud_size); + int valgrind_check = 0; + + + // std::vector>> matData; + //_thread_vec = std::make_shared(_num_threads); + tbb::task_scheduler_init tbb_init(_num_threads); + // _thread_vec(_num_threads); + // ROS_INFO_STREAM("") + + int curr_frame = 0; + int frame_of_interest = 9; + int accumulated_scan = 1; + std::vector> ordered_buff(_beam_num); + while (ros::ok()) { + _lidartag_pose_array.detections.clear(); + detectionsToPub.detections.clear(); + if (_debug_time) { + _timing = + {std::chrono::steady_clock::now(), + std::chrono::steady_clock::now(), + std::chrono::steady_clock::now(), + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + } + + if (_debug_decoding_time) { + _time_decoding = + {std::chrono::steady_clock::now(), + 0, 0, 0, 0, 0, 0, 0, 0}; + } + + // Try to take a pointcloud from the buffer + if (_num_accumulation == 1) { + ordered_buff = LiDARTag::_getOrderBuff(); + if (ordered_buff.empty()) { + continue; + } + } else { + std::vector> ordered_buff_cur = + LiDARTag::_getOrderBuff(); + if (ordered_buff_cur.empty()) { + continue; + } + if (accumulated_scan < _num_accumulation) { + for (int ring = 0; ring < _beam_num; ++ring) { + ordered_buff[ring].insert( + ordered_buff[ring].end(), + ordered_buff_cur[ring].begin(), + ordered_buff_cur[ring].end()); + } + accumulated_scan ++; + _point_cloud_size += _point_cloud_size; + continue; + } + accumulated_scan = 1; + } + + + // cout << "Frame: " << curr_frame << endl; + // if (++curr_frame < frame_of_interest) { + // continue; + // } else if (curr_frame > frame_of_interest) { + // break; + // } + + // A vector of clusters + std::vector clusterbuff; + + pcl::PointCloud::Ptr extracted_poi_pc = + LiDARTag::_lidarTagDetection(ordered_buff, clusterbuff); + + + if (_log_data) + _printStatistics(clusterbuff); + + clusterpc->clear(); + clusteredgepc->clear(); + payloadpc->clear(); + payload3dpc->clear(); + tagpc->clear(); + ini_tagpc->clear(); + boundarypc->clear(); + // indexpc->clear(); + edge_group1->clear(); + edge_group2->clear(); + edge_group3->clear(); + edge_group4->clear(); + for (int ring = 0; ring < _beam_num; ++ring) { + std::vector().swap(ordered_buff[ring]); + } + _point_cloud_size = 0; + + // // assigning indices clockwise and + // // rings start from bottom to down (topmost is 32, for example) + // for(int ring_number =_beam_num-1; ring_number >= 0; --ring_number) { + // for (int index=0; index<_np_ring; index++) { + // indexpc->push_back(ordered_buff[ring_number][index].point); + // } + // } + //publish detectionArray + // LiDARTag::_detectionArrayPublisher(clusterbuff); + // Prepare results for rviz + visualization_msgs::MarkerArray cluster_markers; + LiDARTag::_clusterToPclVectorAndMarkerPublisher( + clusterbuff, clusterpc, clusteredgepc, payloadpc, payload3dpc, + tagpc, ini_tagpc, edge_group1, edge_group2, edge_group3, + edge_group4, boundarypc, cluster_markers); + // add clusters to mat files + // LiDARTag::_saveTemporalCluster(clusterbuff, matData); + + // publish lidartag poses + _lidartag_pose_pub.publish(_lidartag_pose_array); + + // publish results for rviz + LiDARTag::_plotIdealFrame(); + LiDARTag::_publishPC( + extracted_poi_pc, _pub_frame, string("wholeedge")); + LiDARTag::_publishPC( + clusteredgepc, _pub_frame, string("clusteredgepc")); + LiDARTag::_publishPC( + clusterpc, _pub_frame, string("Cluster")); + // LiDARTag::_publishPC( + // indexpc, _pub_frame, string("Indexcolumn")); + LiDARTag::_publishPC( + edge_group1, _pub_frame, string("edgegroup1")); + LiDARTag::_publishPC( + edge_group2, _pub_frame, string("edgegroup2")); + LiDARTag::_publishPC( + edge_group3, _pub_frame, string("edgegroup3")); + LiDARTag::_publishPC( + edge_group4, _pub_frame, string("edgegroup4")); + LiDARTag::_publishPC( + boundarypc, _pub_frame, string("boundarypc")); + + if (_collect_dataset){ + if (_result_statistics.remaining_cluster_size==1) { + LiDARTag::_publishPC( + payloadpc, _pub_frame, string("Payload")); + LiDARTag::_publishPC( + payload3dpc, _pub_frame, string("Payload3D")); + LiDARTag::_publishPC( + tagpc, _pub_frame, string("Target")); + LiDARTag::_publishPC( + ini_tagpc, _pub_frame, string("InitialTarget")); + } + else if (_result_statistics.remaining_cluster_size>1) + cout << "More than one!! " << endl; + else + cout << "Zero!! " << endl; + } else { + LiDARTag::_publishPC( + payloadpc, _pub_frame, string("Payload")); + LiDARTag::_publishPC( + payload3dpc, _pub_frame, string("Payload3D")); + LiDARTag::_publishPC( + tagpc, _pub_frame, string("Target")); + LiDARTag::_publishPC( + ini_tagpc, _pub_frame, string("InitialTarget")); + } + //exit(0); + if (_sleep_to_display) duration.sleep(); + if (_debug_time) { + _timing.total_time = + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), + _timing.start_total_time); + } + // ROS_INFO_STREAM("Hz (total): " << 1e3/_timing.total_time); + // cout << "\033[1;31m====================================== \033[0m\n"; + if (_valgrind_check){ + valgrind_check++; + if (valgrind_check > 0) { + _stop = 1; + break; + } + } + } // ros::ok() + // LiDARTag::_saveMatFiles(matData); + } + + /* + * A function to get all parameters from a roslaunch + * if not get all parameters then it will use hard-coded parameters + */ + void LiDARTag::_getParameters(){ + bool GotThreshold = + ros::param::get("distance_threshold", _distance_threshold); + bool GotPublishTopic = + ros::param::get("lidartag_detection_topic",lidartag_detection_topic); + bool GotSleepToDisplay = + ros::param::get("sleep_to_display", _sleep_to_display); + bool GotSleepTimeForVis = + ros::param::get("sleep_time_for_visulization", _sleep_time_for_vis); + bool GotValgrindCheck = + ros::param::get("valgrind_check", _valgrind_check); + bool GotFakeTag = ros::param::get("fake_data", _fake_tag); + bool GotCSV = ros::param::get("write_csv", _write_CSV); + bool GotMarkValidity = ros::param::get("mark_cluster_validity", _mark_cluster_validity); + bool GotPlaneFitting = ros::param::get("plane_fitting", _plane_fitting); + bool GotOptPose = ros::param::get("optimize_pose", _pose_optimization); + bool GotDecodeId = ros::param::get("decode_id", _id_decoding); + bool GotAssignId = ros::param::get("assign_id", _assign_id); + bool GotRingState = ros::param::get("has_ring", _has_ring); + bool GotRingEstimation = ros::param::get("estimate_ring", _ring_estimation); + bool GotAdaptiveThresholding = + ros::param::get("adaptive_thresholding", _adaptive_thresholding); + bool GotCollectData = + ros::param::get("collect_data", _collect_dataset); + + bool GotLidarTopic = + ros::param::get("pointcloud_topic", _pointcloud_topic); + bool GotBeamNum = ros::param::get("beam_number", _beam_num); + //bool GotSize = ros::param::get("tag_size", _payload_size); + + bool GotTagFamily = ros::param::get("tag_family", _tag_family); + bool GotTagHamming = + ros::param::get("tag_hamming_distance", _tag_hamming_distance); + bool GotMaxDecodeHamming = + ros::param::get("max_decode_hamming", _max_decode_hamming); + bool GotBlackBorder = ros::param::get("black_border", _black_border); + + bool GotDistanceBound = + ros::param::get("distance_bound", _distance_bound); + bool GotIntensityBound = + ros::param::get("intensity_bound", _intensity_threshold); + bool GotDepthBound = ros::param::get("depth_bound", _depth_threshold); + bool GotFineClusterThreshold = + ros::param::get("fine_cluster_threshold", _fine_cluster_threshold); + bool GotVerticalFOV = ros::param::get("vertical_fov", _vertical_fov); + bool GotFillInGapThreshold = + ros::param::get("fill_in_gap_threshold", _filling_gap_max_index); + // bool GotFillInMaxPointsThreshold = + // ros::param::get( + // "fill_in_max_points_threshold", + // fill_in_max_points_threshold); + bool GotPointsThresholdFactor = + ros::param::get( + "points_threshold_factor", _points_threshold_factor); + bool GotLineIntensityBound = + ros::param::get("line_intensity_bound", _line_intensity_bound); + bool GotPayloadIntensityThreshold = + ros::param::get( + "payload_intensity_threshold", + _payload_intensity_threshold); + + bool GotLatestModel = ros::param::get("latest_model", _latest_model); + bool GotWeightPath = ros::param::get("weight_path", _weight_path); + + bool GotMaxPointsOnPayload = + ros::param::get("max_points_on_payload", _max_point_on_payload); + bool GotXYZRI = ros::param::get("xyzri", _XYZRI); + bool GotMinPerGrid = + ros::param::get("min_retrun_per_grid", _min_returns_per_grid); + bool GotOptimizationMethod = + ros::param::get("optimization_solver", _optimization_solver); + bool GotDecodeMethod = + ros::param::get("decode_method", _decode_method); + bool GotDecodeMode = + ros::param::get("decode_mode", _decode_mode); + bool GotGridViz = ros::param::get("grid_viz", _grid_viz); + + // bool GotStatsFilePath = + // ros::param::get("stats_file_path", _stats_file_path); + // bool GotClusterFilePath = + // ros::param::get("cluster_file_path", _cluster_file_path); + // bool GotPoseFilePath = + // ros::param::get("pose_file_path", _pose_file_path); + bool GotOutPutPath = ros::param::get("outputs_path", _outputs_path); + bool GotLibraryPath = ros::param::get("library_path", _library_path); + bool GotNumCodes = ros::param::get("num_codes", _num_codes); + + bool GotDistanceToPlaneThreshold = + ros::param::get( + "distance_to_plane_threshold", + _distance_to_plane_threshold); + bool GotMaxOutlierRatio = + ros::param::get("max_outlier_ratio", _max_outlier_ratio); + bool GotNumPoints = + ros::param::get("num_points_for_plane_feature", + _num_points_for_plane_feature); + bool GotNearBound = ros::param::get("nearby_factor", _nearby_factor); + bool GotNumPointsRing = + ros::param::get("number_points_ring", _np_ring); + bool GotCoefficient = + ros::param::get("linkage_tunable", _linkage_tunable); + bool GotTagSizeList = ros::param::get("tag_size_list", _tag_size_list); + bool GotDerivativeMethod = ros::param::get("euler_derivative", _derivative_method); + bool GotNumThreads = ros::param::get("num_threads", _num_threads); + bool GotPrintInfo = ros::param::get("print_info", _print_ros_info); + bool GotDebuginfo = ros::param::get("debug_info", _debug_info); + bool GotDebugtime = ros::param::get("debug_time", _debug_time); + bool GotDebugDecodingtime = + ros::param::get("debug_decoding_time", _debug_decoding_time); + bool GotLogData = ros::param::get("log_data", _log_data); + bool GotOptimizePercent = + ros::param::get("optimize_percentage", _optimization_percent); + bool GotCalibration = ros::param::get("calibration", _calibration); + bool GotMinimumRingPoints = + ros::param::get("minimum_ring_boundary_points", _minimum_ring_boundary_points); + bool GotUpbound = ros::param::get("optimize_up_bound", _opt_ub); + bool GotLowbound = ros::param::get("optimize_low_bound", _opt_lb); + bool GotNumAccumulation = + ros::param::get("num_accumulation", _num_accumulation); + bool GotCoaTunable = ros::param::get("coa_tunable", _coa_tunable); + bool GotTagsizeTunable = ros::param::get("tagsize_tunable", _tagsize_tunable); + bool Pass = utils::checkParameters(64, + GotFakeTag, GotLidarTopic, GotBeamNum, + GotOptPose, GotDecodeId, GotPlaneFitting, + GotAssignId, GotCSV, GotOutPutPath, + GotDistanceBound, GotIntensityBound, GotDepthBound, + GotTagFamily, GotTagHamming, GotMaxDecodeHamming, + GotFineClusterThreshold, GotVerticalFOV, GotFillInGapThreshold, + GotMaxOutlierRatio, GotPointsThresholdFactor, GotLineIntensityBound, + GotDistanceToPlaneThreshold, GotAdaptiveThresholding, GotCollectData, + GotSleepToDisplay, GotSleepTimeForVis, GotValgrindCheck, + GotPayloadIntensityThreshold, GotLatestModel, GotWeightPath, + GotBlackBorder, GotMaxPointsOnPayload, GotXYZRI, + GotMinPerGrid, GotDecodeMethod, GotDecodeMode, + GotOptimizationMethod, GotGridViz, GotPublishTopic, + GotThreshold, GotNumPoints, GotNearBound, + GotNumPointsRing, GotCoefficient, GotTagSizeList, + GotNumThreads, GotPrintInfo, GotOptimizePercent, + GotDebuginfo, GotDebugtime, GotLogData, + GotDebugDecodingtime, GotLibraryPath, GotNumCodes, + GotCalibration, GotMinimumRingPoints, GotRingState, + GotRingEstimation, GotNumAccumulation, GotDerivativeMethod, + GotUpbound, GotLowbound, GotCoaTunable, + GotTagsizeTunable); + + if (!Pass){ + // TODO: check compleness + cout << "\033[1;32m=========================== \033[0m\n"; + cout << "use hard-coded parameters\n"; + cout << "\033[1;32m=========================== \033[0m\n"; + + // Default value + _distance_threshold = 10; + _pointcloud_topic = "/velodyne_points"; + lidartag_detection_topic = + "/LiDARTag/lidar_tag/LiDARTagDetectionArray"; + _beam_num = 32; + _distance_bound = 7; // for edge gradient + _intensity_threshold = 2; // for edge gradient + _depth_threshold = 0.5; // for edge gradient + _payload_intensity_threshold = 30; + //_payload_size = 0.15; + + _tag_family = 16; + _tag_hamming_distance = 5; + _max_decode_hamming = 2; + + // if the points in a cluster is small than this, it'd get dropped + _fine_cluster_threshold = 20; + _vertical_fov = 40; + + // When fill in the cluster, + // if it the index is too far away then drop it + // TODO:Need a beteer way of doing it! + _filling_gap_max_index = 200; + _filling_max_points_threshold = 4500; + + _line_intensity_bound = 1000; // To determine the payload edge + + // if the points on a "valid" tag is less than this factor, + // then remove it (the higher, the looser) + _points_threshold_factor = 1.3; + _adaptive_thresholding = 0; + _collect_dataset = 1; + + _sleep_to_display = 1; + _sleep_time_for_vis = 0.05; + _valgrind_check = 0; + _black_border = 1; + _fake_tag = 0; + + _latest_model = "-337931"; + _weight_path = "/weight/"; + _max_point_on_payload = 150; + _XYZRI = 4 ; + _min_returns_per_grid = 3; + _decode_method = 2; + _grid_viz = 1; + + _distance_to_plane_threshold = 0.1; + _max_outlier_ratio = 0.1; + _num_points_for_plane_feature = 3; + _np_ring = 10; + _linkage_tunable = 1.0; + _optimization_percent = 0.1; + _tag_size_list = {0.7}; + _debug_info = false; + _debug_time = false; + _plane_fitting = true; + _has_ring = true; + _ring_estimation = true; + _derivative_method = true; + _opt_lb = 0.8; + _opt_ub = 0.8; + _coa_tunable = 0.75; + _tagsize_tunable = 1.5; + } + else{ + cout << "\033[1;32m=========================== \033[0m\n"; + cout << "use parameters from the launch file\n"; + cout << "\033[1;32m=========================== \033[0m\n"; + } + std::sort(_tag_size_list.begin(), _tag_size_list.end()); + _num_tag_sizes = _tag_size_list.size(); + _payload_size = _tag_size_list.back(); + + const auto num_processor = std::thread::hardware_concurrency(); + _num_threads = std::min((int) num_processor, _num_threads); + + _iter = 0; + + // point association threshold (which cluster the point belongs to?) + // cout << "_linkage_tunable: " << _linkage_tunable << endl; + _linkage_threshold = _linkage_tunable * _payload_size * SQRT2 / 4; + if (_has_ring) { + _use_ring = true; + } else { + if (_ring_estimation) { + _use_ring = true; + } else { + _use_ring = false; + } + } + // cout << "link threshold: " << _linkage_threshold << endl; + // exit(0); + _RANSAC_threshold = _payload_size/10; + + ROS_INFO("Subscribe to %s\n", _pointcloud_topic.c_str()); + ROS_INFO("Use %i-beam LiDAR\n", _beam_num); + ROS_INFO("Use %i threads\n", _num_threads); + ROS_INFO("_intensity_threshold: %f \n", _intensity_threshold); + ROS_INFO("_depth_threshold: %f \n", _depth_threshold); + ROS_INFO("_payload_size: %f \n", _payload_size); + ROS_INFO("_vertical_fov: %f \n", _vertical_fov); + ROS_INFO("_fine_cluster_threshold: %i \n", _fine_cluster_threshold); + ROS_INFO("_filling_gap_max_index: %i \n", _filling_gap_max_index); + // ROS_INFO("_filling_max_points_threshold: %i \n", + // _filling_max_points_threshold); + ROS_INFO("_points_threshold_factor: %f \n", _points_threshold_factor); + ROS_INFO("_adaptive_thresholding: %i \n", _adaptive_thresholding); + ROS_INFO("_collect_dataset: %i \n", _collect_dataset); + ROS_INFO("_decode_method: %i \n", _decode_method); + ROS_INFO("linkage_hreshold_: %f \n", _linkage_threshold); + ROS_INFO("_RANSAC_threshold: %f \n", _RANSAC_threshold); + ROS_INFO("_num_accumulation: %i \n", _num_accumulation); + + usleep(2e6); + } + + + /* + * A function to get pcl ordered_buff + * from a ros sensor-msgs form of pointcould queue + * */ + std::vector> + LiDARTag::_getOrderBuff(){ + _point_cloud1_queue_lock.lock(); + // ;boost::mutex::scoped_lock(_point_cloud1_queue_lock); + if (_point_cloud1_queue.size()==0) { + _point_cloud1_queue_lock.unlock(); + + //cout << "Pointcloud queue is empty" << endl; + //cout << "size: " << empty.size() << endl; + vector> empty; + return empty; + } + // ROS_INFO_STREAM("Queue size: " << _point_cloud1_queue.size()); + + sensor_msgs::PointCloud2ConstPtr msg = _point_cloud1_queue.front(); + _point_cloud1_queue.pop(); + _point_cloud1_queue_lock.unlock(); + _current_scan_time = msg->header.stamp; + + // Convert to sensor_msg to pcl type + pcl::PointCloud::Ptr + pcl_pointcloud(new pcl::PointCloud); + pcl::fromROSMsg(*msg, *pcl_pointcloud); + + + if (!_has_ring && !_ring_estimated) { + std::vector angles; + _getAngleVector(pcl_pointcloud, angles); + // cout << "angles_size" <size(); ++i) { + fangles << angles[i] << ","; + } + // fangles << angles; + fangles << std::endl; + fangles.close(); + _ring_estimated = true; + vector> empty; + return empty; + } + + // Ordered pointcloud with respect to its own ring number + std::vector> ordered_buff(_beam_num); + _fillInOrderedPC(pcl_pointcloud, ordered_buff); + _point_cloud_size = pcl_pointcloud->size(); + // cout << "pc size: " << _point_cloud_size << endl; + + return ordered_buff; + } + + + /* + * A function to get a LiDAR system parameters such as max, + * min points per scan and how many points per ring + * The data format is: + * + * (A) point_count_table: + * point_count_table[Scan][Ring] + * ----------------------------------------- + * 1 2 3 4 5 6 7 ... scan + * ----------------------------------------- + * 0 17xx ... + * ----------------------------------------- + * 1 16xx ... + * ----------------------------------------- + * 2 + * . + * . + * . + * 31 + * ring + * + * + * (B) max_min_table: + * ---------------------------------------- + * 1 2 3 .... scan + * Max Max Max + * Min Min Min + * --------------------------------------- + */ + void LiDARTag::_analyzeLiDARDevice(){ + _ring_estimated = false; + _LiDAR_system.point_count_table.resize(100); + _LiDAR_system.ring_average_table.reserve(_beam_num); + + // Initialize the table + MaxMin_t max_min{(int)1e5, -1, -1}; // min, ave, max + + for (int j=0; j<_beam_num; ++j) { + _LiDAR_system.ring_average_table.push_back(max_min); + } + + // if (!_has_ring && _ring_estimation) { + // while (ros::ok()) { + // std::vector> ordered_buff = + // LiDARTag::_getOrderBuff(true); + // if (ordered_buff.empty()) { + // continue; + // } + // if (!_has_ring && _ring_estimation && _ring_estimated) + // break; + // } + // } + + + // Calulate for each scan with a few seconds + int i = 0; + int num_scan = 0; + clock_t begin = clock(); + int accumulated_scan = 1; + std::vector> ordered_buff(_beam_num); + while (ros::ok()) { + + if (_num_accumulation == 1) { + ordered_buff = LiDARTag::_getOrderBuff(); + if (ordered_buff.empty()) { + continue; + } + } else { + std::vector> ordered_buff_cur = + LiDARTag::_getOrderBuff(); + if (ordered_buff_cur.empty()) { + continue; + } + if (accumulated_scan < _num_accumulation) { + for (int ring = 0; ring < _beam_num; ++ring) { + ordered_buff[ring].insert( + ordered_buff[ring].end(), + ordered_buff_cur[ring].begin(), + ordered_buff_cur[ring].end()); + } + accumulated_scan ++; + continue; + } + accumulated_scan = 1; + } + + + // cout << "i: " << i++ << endl; + LiDARTag::_maxMinPtsInAScan( + _LiDAR_system.point_count_table[num_scan], + _LiDAR_system.max_min_table, + _LiDAR_system.ring_average_table, + ordered_buff); + num_scan++; + clock_t end = clock(); + for (int ring = 0; ring < _beam_num; ++ring) { + std::vector().swap(ordered_buff[ring]); + } + if ((((double) (end-begin)/ CLOCKS_PER_SEC) > 3) || + num_scan >= 100) { + break; + } + } + // cout << "here"; + for (auto i = _LiDAR_system.ring_average_table.begin(); + i != _LiDAR_system.ring_average_table.end(); + ++i) { + (*i).average /= num_scan; + // cout << "average: " << (*i).average << endl; + } + + LiDARTag::_pointsPerSquareMeterAtOneMeter(); + + // std::vector::iterator it; + // it = std::unique(_LiDAR_system.angle_list.begin(), + // _LiDAR_system.angle_list.end(), angleComparision); + + + + // Check values of pointtable and max_min_table + // int k = 0; + // for (auto i=_LiDAR_system.point_count_table.begin(); i!=_LiDAR_system.point_count_table.end(); ++i, ++k){ + // cout << "Vector[" << k << "]:" << endl; + // for (auto j=(*i).begin(); j!=(*i).end(); ++j){ + // cout << "points: " << *j << endl; + // } + // } + + // k=0; + // for (auto i=_LiDAR_system.max_min_table.begin(); i!=_LiDAR_system.max_min_table.end(); ++i, ++k){ + // cout << "At scan [" << k << "]" << endl; + // cout << "Max: " << (*i).Max << endl; + // cout << "Min: " << (*i).Min << endl; + // } + + // k=0; + // for (auto i=_LiDAR_system.ring_average_table.begin(); i!=_LiDAR_system.ring_average_table.end(); ++i, ++k){ + // cout << "At ring [" << k << "]" << endl; + // cout << "Max: " << (*i).Max << endl; + // cout << "Ave: " << (*i).average << endl; + // cout << "Min: " << (*i).Min << endl; + // } + // exit(0); + } + + + /* + * A function to calculate how many points are supposed to be + * on a cluster at 1 meter away + */ + void LiDARTag::_pointsPerSquareMeterAtOneMeter(){ + double system_average; + for (auto i=_LiDAR_system.ring_average_table.begin(); + i!=_LiDAR_system.ring_average_table.end(); + ++i) { + system_average += (*i).average; + } + system_average /= _LiDAR_system.ring_average_table.size(); + _LiDAR_system.beam_per_vertical_radian = + _beam_num / utils::deg2Rad(_vertical_fov); + _LiDAR_system.point_per_horizontal_radian = + system_average / utils::deg2Rad(360.0); + } + + + /* + * A function to find maximum points and minimum points in a single scan, + * i.e. to find extrema within 32 rings + */ + void LiDARTag::_maxMinPtsInAScan( + std::vector &point_count_table, + std::vector &max_min_table, + std::vector &ring_average_table, + const std::vector>& ordered_buff){ + // every scan should have different largest/ smallest numbers + int largest = -1; + int smallest = 100000; + MaxMin_t max_min; + + int i = 0; + for (auto ring=ordered_buff.begin(); ring!=ordered_buff.end(); ++ring){ + int ring_size = (*ring).size(); + point_count_table.push_back(ring_size); + + // first time (we had initialized with -1) + if (ring_average_table[i].average < 0) { + ring_average_table[i].average = ring_size; + } + else{ + ring_average_table[i].average = + (ring_average_table[i].average + ring_size); + } + + if (ring_average_table[i].max < ring_size){ + ring_average_table[i].max = ring_size; + } + + if (ring_average_table[i].min > ring_size){ + ring_average_table[i].min = ring_size; + } + + if (ring_size > largest) { + largest = ring_size; + max_min.max = ring_size; + } + + if (ring_size < smallest) { + smallest = ring_size; + max_min.min = ring_size; + } + i++; + } + max_min_table.push_back(max_min); + } + + + /* + * A function to transfer pcl msgs to ros msgs and then publish + * which_publisher should be a string of "organized" or "original" + * regardless lowercase and uppercase + */ + void LiDARTag::_publishPC(const pcl::PointCloud::Ptr &source_pc, + const std::string &frame, string which_publisher){ + utils::tranferToLowercase(which_publisher); // check letter cases + sensor_msgs::PointCloud2 pcs_waited_to_pub; + pcl::toROSMsg(*source_pc, pcs_waited_to_pub); + pcs_waited_to_pub.header.frame_id = frame; + + try { + if (which_publisher=="wholeedge") + _edge_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="original") + _original_pc_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="cluster") + _cluster_pub.publish(pcs_waited_to_pub); + // else if (which_publisher=="indexcolumn") + // _index_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="payload") + _payload_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="payload3d") + _payload3d_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="target") + _tag_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="edgegroup1") + _edge1_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="edgegroup2") + _edge2_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="edgegroup3") + _edge3_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="edgegroup4") + _edge4_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="boundarypc") + _boundary_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="initialtarget") + _ini_tag_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="clusteredgepc") + _clustered_points_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="transpts") + _transformed_points_pub.publish(pcs_waited_to_pub); + else if (which_publisher=="transptstag") + _transformed_points_tag_pub.publish(pcs_waited_to_pub); + else { + throw "No such Publisher exists"; + } + } + catch (const char* msg){ + cout << "\033[1;31m========================= \033[0m\n"; + cerr << msg << endl; + cout << "\033[1;31m========================= \033[0m\n"; + exit(-1); + } + } + + + /* [basic ros] + * A function to push the received pointcloud into a queue in the class + */ + void LiDARTag::_pointCloudCallback( + const sensor_msgs::PointCloud2ConstPtr &pc){ + // flag to make sure it receives a pointcloud + // at the very begining of the program + _point_cloud_received = 1; + _point_cloud_header = pc->header; + //boost::mutex::scoped_lock(_point_cloud1_queue_lock); + _point_cloud1_queue_lock.lock(); + _point_cloud1_queue.push(pc); + _point_cloud1_queue_lock.unlock(); + + } + + + /* + * A function to make sure the program has received at least + * one pointcloud at the very start of this program + */ + inline + void LiDARTag::_waitForPC(){ + while (ros::ok()){ + if (_point_cloud_received) { + ROS_INFO("Got pointcloud data"); + return; + } + ros::spinOnce(); + } + } + + + /* + * A function to slice the Veloydyne full points to sliced pointed + * based on ring number + * */ + inline + void LiDARTag::_fillInOrderedPC( + const pcl::PointCloud::Ptr &pcl_pointcloud, + std::vector>& ordered_buff) { + if (!_has_ring && _ring_estimated) { + std::string ring_list; + for (auto &&it : _LiDAR_system.angle_list) + ring_list += (std::to_string(it) + " "); + ROS_INFO_STREAM_ONCE( + "Estimate Ring List Size: " << _LiDAR_system.angle_list.size()); + ROS_INFO_STREAM_ONCE("Estimate Ring List: " << ring_list); + assert(("Ring List Error", + _LiDAR_system.angle_list.size() <= _beam_num)); + } + + + LiDARPoints_t lidar_point; + int index [_beam_num] = {0}; + std::set::iterator it; + for (auto && p : *pcl_pointcloud) { + if (p.x == 0 && p.y == 0 && p.z == 0) { + continue; + } + + if (!_has_ring && _ring_estimated) { + float angle = _getAnglefromPt(p); + it = _LiDAR_system.angle_list.find(angle); + p.ring = + std::distance(_LiDAR_system.angle_list.begin(), it); + // cout << "angle: " << angle << endl; + // if (p.ring==0) { + // cout << "x: " << p.x << endl; + // cout << "y: " << p.y << endl; + // cout << "z: " << p.z << endl; + // cout << "ring: " << p.ring << endl; + // } + + // cout << "point: " << p.x << ", " << p.y << ", " << p.z << ", " << p.ring << endl; + } + // cout << "point: " << p.x << ", " << p.y << ", " << p.z << ", " << p.ring << ", " <::Ptr &pcl_pointcloud, + std::vector &angles) { + for (auto && p : *pcl_pointcloud) { + if (p.x == 0 && p.y == 0 && p.z == 0) { + continue; + } + float angle = LiDARTag::_getAnglefromPt(p); + // utils::COUT(p); + angles.push_back(angle); + _LiDAR_system.angle_list.insert(angle); + // if (_LiDAR_system.angle_list.insert(angle).second == true) { + // cout << "Inserted: " << angle << endl; + // } else { + // cout << "--Rejected: " << angle << endl; + // } + } + } + /* + * Main function + */ + pcl::PointCloud::Ptr + LiDARTag::_lidarTagDetection( + const std::vector>& ordered_buff, + std::vector &cluster_buff){ + + if (_debug_info || _debug_time ) + ROS_INFO_STREAM("--------------- Begining ---------------"); + else + ROS_DEBUG_STREAM("--------------- Begining ---------------"); + + pcl::PointCloud::Ptr out(new pcl::PointCloud); + out->reserve(_point_cloud_size); + + // Buff to store all detected edges + std::vector> edge_buff(_beam_num); + + // calculate gradient for depth and intensity as well as + // group them into diff groups + _result_statistics = {{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, 0, 0, 0, 0}; + + _timing.start_computation_time = std::chrono::steady_clock::now(); + LiDARTag::_gradientAndGroupEdges(ordered_buff, edge_buff, cluster_buff); + if (_debug_time) { + _timing.edging_and_clustering_time = + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), + _timing.start_computation_time); + _timing.timing = std::chrono::steady_clock::now(); + } + + // transform from a vector of vector (edge_buff) into a pcl vector (out) + boost::thread BuffToPclVectorThread( + &LiDARTag::_buffToPclVector, this, boost::ref(edge_buff), out); + if (_debug_time) { + _timing.to_pcl_vector_time = + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + } + + LiDARTag::_fillInCluster(ordered_buff, cluster_buff); + BuffToPclVectorThread.join(); + _result_statistics.point_cloud_size = _point_cloud_size; + _result_statistics.edge_cloud_size = out->size(); + _timing.total_duration = + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), + _timing.start_computation_time); + // std::chrono::duration duration = + // std::chrono::steady_clock::now() - clock_start; + // _timing.duration = duration.count(); + //cout << "Computation time : " << 1.0 / duration.count() << " [Hz]" << endl; + + + + // _timing.duration = duration.count(); + if (_print_ros_info || _debug_info) { + ROS_INFO_STREAM("-- Remaining Cluster: " << + _result_statistics.remaining_cluster_size); + ROS_INFO_STREAM("-- Computation: " << + 1e3 / _timing.total_duration << " [Hz]"); + } + + if (_debug_info){ + ROS_DEBUG_STREAM("--------------- summary ---------------"); + ROS_DEBUG_STREAM("-- Original cloud size: " << + _result_statistics.point_cloud_size); + ROS_DEBUG_STREAM("-- Edge cloud size: " << + _result_statistics.edge_cloud_size); + ROS_DEBUG_STREAM("-- Original cluster: " << + _result_statistics.original_cluster_size); + ROS_DEBUG_STREAM("-- Removed by minimum returns: " << + _result_statistics.cluster_removal.minimum_return); + ROS_DEBUG_STREAM("-- Removed by maximum returns: " << + _result_statistics.cluster_removal.maximum_return); + ROS_DEBUG_STREAM("-- Removed by plane fitting failure: " << + _result_statistics.cluster_removal.plane_fitting); + ROS_DEBUG_STREAM("-- Removed by plane fitting ourliers: " << + _result_statistics.cluster_removal.plane_outliers); + ROS_DEBUG_STREAM("-- Removed by payload boundary point: " << + _result_statistics.cluster_removal.boundary_point_check); + ROS_DEBUG_STREAM("-- Removed by payload ring points: " << + _result_statistics.cluster_removal.minimum_ring_points); + ROS_DEBUG_STREAM("-- Removed by edge points: " << + _result_statistics.cluster_removal.no_edge_check); + ROS_DEBUG_STREAM("-- Removed by line fitting: " << + _result_statistics.cluster_removal.line_fitting); + ROS_DEBUG_STREAM("-- Removed by pose optimization: " << + _result_statistics.cluster_removal.pose_optimization); + ROS_DEBUG_STREAM("-- Removed by decoding: " << + _result_statistics.cluster_removal.decoding_failure); + ROS_DEBUG_STREAM("-- Remaining Cluster: " << + _result_statistics.remaining_cluster_size); + ROS_DEBUG_STREAM("---------------------------------------"); + } + if (_debug_time) { + ROS_DEBUG_STREAM("--------------- Timing ---------------"); + ROS_DEBUG_STREAM("computation_time: " << + 1e3 / _timing.total_duration << " [Hz]"); + ROS_DEBUG_STREAM("edging_and_clustering_time: " << + _timing.edging_and_clustering_time); + + ROS_DEBUG_STREAM("to_pcl_vector_time: " << _timing.to_pcl_vector_time); + + ROS_DEBUG_STREAM("fill_in_time: " << _timing.fill_in_time); + + ROS_DEBUG_STREAM("point_check_time: " << _timing.point_check_time); + + ROS_DEBUG_STREAM("line_fitting_time: " << _timing.line_fitting_time); + + ROS_DEBUG_STREAM("organize_points_time: " << + _timing.organize_points_time); + + ROS_DEBUG_STREAM("pca_time: " << _timing.pca_time); + + ROS_DEBUG_STREAM("split_edge_time: " << _timing.split_edge_time); + + ROS_DEBUG_STREAM("pose_optimization_time: " << + _timing.pose_optimization_time); + + ROS_DEBUG_STREAM("store_template_time: " << _timing.store_template_time); + + ROS_DEBUG_STREAM("payload_decoding_time: " << + _timing.payload_decoding_time); + ROS_DEBUG_STREAM("computation_time: " << _timing.total_duration); + ROS_DEBUG_STREAM("---------------------------------------"); + // cout << "payload_decoding_time: " << _timing.payload_decoding_time << endl; + // ROS_DEBUG_STREAM("PointCheck: " << _timing.point_check_time); + // ROS_DEBUG_STREAM("LineFitting: " << _timing.line_fitting_time); + // //ROS_DEBUG_STREAM("ExtractPayload: " << _timing.payload_extraction_time); + // ROS_DEBUG_STREAM("NormalVector: " << _timing.normal_vector_time); + // ROS_DEBUG_STREAM("PayloadDecoder: " << + // _timing.payload_decoding_time); + // ROS_DEBUG_STREAM("_tagToRobot: " << _timing.tag_to_robot_time); + } + + return out; + } + + + /* + * A function to + * (1) calculate the depth gradient and + * the intensity gradient at a point of a pointcloud + * (2) group detected 'edge' into different group + */ + void LiDARTag::_gradientAndGroupEdges( + const std::vector>& ordered_buff, + std::vector>& edge_buff, + std::vector &cluster_buff) { + + int n = _num_points_for_plane_feature; + // clock_t start = clock(); + // TODO: if suddently partial excluded, it will cause errors + for(int i=_beam_num-1; i >= 0; --i) { + int size = ordered_buff[i].size(); + for(int j=1; j= 0; --i) { + // int size = ordered_buff[i].size(); + // for(int j=2; j _distance_bound || + // std::abs(point.y) > _distance_bound || + // std::abs(point.z) > _distance_bound) continue; + // const auto& PointL = ordered_buff[i][j-1].point; + // const auto& PointR = ordered_buff[i][j+1].point; + // double DepthGrad = std::max((PointL.getVector3fMap()-point.getVector3fMap()).norm(), + // (point.getVector3fMap()-PointR.getVector3fMap()).norm()); + + // // double IntenstityGrad = std::max(std::abs(PointL.intensity - point.intensity), + // // std::abs(point.intensity - PointR.intensity)); + + // // if (IntenstityGrad > _intensity_threshold && + // // DepthGrad > _depth_threshold) { + // if (DepthGrad > _depth_threshold) { + // // Cluster the detected 'edge' into different groups + // _clusterClassifier(ordered_buff[i][j], cluster_buff); + + // // push the detected point that is an edge into a buff + // LiDARPoints_t LiDARPoints = {ordered_buff[i][j].point, ordered_buff[i][j].index, + // DepthGrad, 0}; + // edge_buff[i].push_back(LiDARPoints); + // } + // } + // } + + //double DepthGrad = std::abs((PointL.getVector3fMap()-point.getVector3fMap()).norm()- + // (point.getVector3fMap()-PointR.getVector3fMap()).norm()); + + // Remove all clusters with insufficient points + // pcl::PointCloud::Ptr ClusterEdgePC(new pcl::PointCloud); + // for (int i = 0; i < cluster_buff.size(); ++i) + // { + // if (cluster_buff[i].data.size() >= std::sqrt(_tag_family)*2) + // { + // for (const auto & lidar_point : cluster_buff[i].data) + // { + // ClusterEdgePC->push_back(lidar_point.point); + // } + // } + // } + + // cout << "Number of Total Clusters: " << cluster_buff.size() << endl; + + // Publish edge points in large clusters + // LiDARTag::_publishPC(ClusterEdgePC, _pub_frame, string("clusteredgepc")); + + // clock_t end = clock(); + // cout << "extraction hz: " << 1/ (((double) (end - start))/clocks_per_sec) << endl; + // } + + /* + * A function to + * (1) kick out points are not near to each other + * (2) find edge points from two side points of these points + */ + int LiDARTag::_getEdgePoints( + const std::vector>& ordered_buff, + int i, int j, int n) { + const auto& point = ordered_buff[i][j].point; + if (std::abs(point.x) > _distance_bound || + std::abs(point.y) > _distance_bound || + std::abs(point.z) > _distance_bound) + return 0; + + // cout << "average on " << i << " ring: " << + // _LiDAR_system.ring_average_table[i].average << endl; + + double point_resolution = + 2 * M_PI / _LiDAR_system.ring_average_table[i].average; + double near_bound = std::max(0.1, _nearby_factor * + point.getVector3fMap().norm() * std::sin(point_resolution)); + // cout << "near bound: " << near_bound << endl; + // double near_bound = _nearby_factor; + for(int k=0; k near_bound) + if (distance > near_bound) + return 0; + } + const auto& point2 = ordered_buff[i][j+n-1].point; + const auto& PointL = ordered_buff[i][j-1].point; + const auto& PointR = ordered_buff[i][j+1].point; + const auto& Point2L = ordered_buff[i][j+n-2].point; + const auto& Point2R = ordered_buff[i][j+n].point; + double DepthGrad1 = + std::abs((PointL.getVector3fMap()-point.getVector3fMap()).norm()- + (point.getVector3fMap()-PointR.getVector3fMap()).norm()); + double DepthGrad2 = + std::abs((Point2L.getVector3fMap()-point2.getVector3fMap()).norm()- + (point2.getVector3fMap()-Point2R.getVector3fMap()).norm()); + if (DepthGrad1 > _depth_threshold) { + if (DepthGrad2 > _depth_threshold) { + return 3; + } else { + return 1; + } + } else { + if (DepthGrad2 > _depth_threshold) { + return 2; + } else { + return 0; + } + } + } + + + /* + * A function to + * (1) remove invalid cluster based on the index is too far or not + * (2) fill in the points between index of edges + * (3) after filling, if the points are too less (based on the analyzed system + * and given distant of the cluster), then remove this cluster + * (4) Adaptive thresholding (Maximize and minimize intensity) by comparing + * with the average value + */ + void LiDARTag::_fillInCluster( + const std::vector>& ordered_buff, + std::vector &cluster_buff){ + std::ofstream fplanefit; + if (_log_data) { + std::string path(_outputs_path); + fplanefit.open(path + "/planeFit.txt"); + if (!fplanefit.is_open()) { + cout << "Could not open planeFit.txt" << endl; + exit(0); + } + } + + // _debug_cluster.boundary_point.clear(); + _result_statistics.original_cluster_size = cluster_buff.size(); + _result_statistics.remaining_cluster_size = cluster_buff.size(); + + // tbb::parallel_for(int(0), (int)cluster_buff.size(), [&](int i) { + for (int i=0; i < cluster_buff.size(); ++i){ + // In a cluster + // tbb::parallel_for(int(0), (int)cluster_buff.size(), [&](int i) { + if (_debug_time) { + _timing.timing = std::chrono::steady_clock::now(); + } + for (int j=0; j<_beam_num; ++j){ + int max_index = + cluster_buff[i].max_min_index_of_each_ring[j].max; + int min_index = + cluster_buff[i].max_min_index_of_each_ring[j].min; + + // no points on this ring + if ((std::abs(min_index - 1e5) < 1e-5) || + std::abs(max_index + 1) < 1e-5) { + continue; + } + + // A cluster can't cover 180 FoV of a LiDAR! + // If max and min indices are larger than this, + // that means the special case happened + // The special case is when first point of a ring is in this cluster + // so the indices are not consecutive + double fill_in_gap = _LiDAR_system.ring_average_table[j].average / 2; + // cout << "(i, j) = (" << i << ", " << j << ")" << endl; + // cout << "fill_in_gap: " << fill_in_gap << endl; + // cout << "max index: " << max_index << endl; + // cout << "min index: " << min_index << endl; + + // if (max_index-min_index < _filling_gap_max_index) { + if (max_index - min_index < fill_in_gap) { + // remove minimum index itself + // (it has been in the cloud already) + for (int k = min_index + 1; k < max_index; ++k) { + // cout << "k1: " << k << endl; + if (_isWithinClusterHorizon( + ordered_buff[j][k], cluster_buff[i], 0)) { + cluster_buff[i].data.push_back(ordered_buff[j][k]); + } + } + cluster_buff[i].special_case = 0; + } else { + for (int k = 0; k < min_index; ++k) { + // cout << "k2: " << k << endl; + if (_isWithinClusterHorizon( + ordered_buff[j][k], cluster_buff[i], 0)) { + cluster_buff[i].data.push_back(ordered_buff[j][k]); + } + } + for (int k = max_index; k < ordered_buff[j].size(); ++k) { + // cout << "k3: " << k << endl; + if (_isWithinClusterHorizon( + ordered_buff[j][k], cluster_buff[i], 0)) { + cluster_buff[i].data.push_back(ordered_buff[j][k]); + } + } + cluster_buff[i].special_case = 1; + } + } + if (_debug_time) { + _timing.fill_in_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + // Mark cluster as invalid if too few points in cluster + auto min_returns = _min_returns_per_grid* + std::pow((std::sqrt(_tag_family)+2*_black_border), 2); + if ((cluster_buff[i].data.size() + + cluster_buff[i].edge_points.size()) < min_returns) { + _result_statistics.cluster_removal.minimum_return ++; + _result_statistics.remaining_cluster_size--; + + if (_mark_cluster_validity) + cluster_buff[i].valid = false; + //tbb::task::self().cancel_group_execution(); + continue; + } + + // Mark cluster as invalid if too many points in cluster + _maxPointsCheck(cluster_buff[i]); + if (cluster_buff[i].valid == false) { + //tbb::task::self().cancel_group_execution(); + continue; + } + if (_debug_time) { + _timing.point_check_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + // Mark cluster as invalid if unable to perform plane fitting + if (!_plane_fitting) { + continue; + } else { + pcl::PointIndices::Ptr inliers (new pcl::PointIndices); + pcl::ModelCoefficients::Ptr coefficients ( + new pcl::ModelCoefficients); + if (!_rejectWithPlanarCheck( + cluster_buff[i], inliers, coefficients, fplanefit)) { + if (_mark_cluster_validity) + cluster_buff[i].valid = false; + //tbb::task::self().cancel_group_execution(); + continue; + } + + // Mark cluster as invalid if too many outliers in plane fitting + auto percentage_inliers = + inliers->indices.size() / + double(cluster_buff[i].data.size() + + cluster_buff[i].edge_points.size()); + cluster_buff[i].percentages_inliers = percentage_inliers; + + if (_debug_info) { + ROS_DEBUG_STREAM("==== _planeOutliers ===="); + float distance = + std::sqrt(pow(cluster_buff[i].average.x, 2) + + pow(cluster_buff[i].average.y, 2) + + pow(cluster_buff[i].average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster_buff[i].data.size() + + cluster_buff[i].edge_points.size()); + } + + if (percentage_inliers < (1.0 - _max_outlier_ratio)) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + //tbb::task::self().cancel_group_execution(); + _result_statistics.cluster_removal.plane_outliers++; + _result_statistics.remaining_cluster_size--; + if (_mark_cluster_validity) { + cluster_buff[i].valid = false; + continue; + } + } + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << true); + + // Remove all outliers from cluster + auto outliers_indices = + utils::complementOfSet( + inliers->indices, + (cluster_buff[i].data.size() + + cluster_buff[i].edge_points.size())); + int edge_inlier = cluster_buff[i].edge_points.size(); + for (int k = 0; k < outliers_indices.size(); ++k) { + int out_index = outliers_indices[k]; + if (out_index < cluster_buff[i].edge_points.size()) { + edge_inlier -= 1; + cluster_buff[i].edge_points[out_index].valid = 0; + } else { + cluster_buff[i].data[ + out_index - cluster_buff[i].edge_points.size()].valid = 0; + } + } + cluster_buff[i].edge_inliers = edge_inlier; + if (_debug_time) { + _timing.plane_fitting_removal_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + } + + // utils::removeIndicesFromVector( + // cluster_buff[i].data, outliers_indices + // ); + // If the points in this cluster after filling are still less than the + // factored threshold, then remove it + // _timing.timing = clock(); + // if(!_clusterPointsCheck(cluster_buff[i])){ + // _timing.point_check_time += utils::spendTime(clock(), _timing.timing); + // //cout << "cluster removed" << endl; + // cluster_buff[i].valid = 0; + // //cluster_buff.erase(cluster_buff.begin()+i); + // // _debug_cluster.point_check.push_back(&cluster_buff[i]); + // //i--; + // _result_statistics.remaining_cluster_size -= 1; + // _result_statistics.cluster_removal.removed_by_point_check ++; + // } + // Adaptive thresholding (Maximize and minimize intensity) by comparing + // with the average value + // else { + // _timing.point_check_time += utils::spendTime(clock(), _timing.timing); + // boost::thread BuffToPclVectorThread(&LiDARTag::AdaptiveThresholding, this, boost::ref(cluster_buff[i])); + if(!LiDARTag::_adaptiveThresholding(cluster_buff[i])) { + // removal has been done inside the function + if (_mark_cluster_validity) + cluster_buff[i].valid = false; + // cluster_buff.erase(cluster_buff.begin()+i); + // i--; + } else { + if (_print_ros_info || _debug_info) { + ROS_INFO_STREAM("--ID: " << + cluster_buff[i].cluster_id); + ROS_INFO_STREAM("---rotation: " << + cluster_buff[i].rkhs_decoding.rotation_angle); + } + } + // } + } + //}, tbb::auto_partitioner()); + + // Collect histogram data of cluster + // ofstream clusterHist("/home/cassie/catkin_ws/src/LiDARTag/output/hist.txt"); + // pcl::PointCloud::Ptr ClusterEdgePC(new pcl::PointCloud); + // for (int i = 0; i < cluster_buff.size(); ++i) { + // if (!cluster_buff[i].valid) { + // continue; + // } + // clusterHist << i << " " << cluster_buff[i].data.size() << endl; + + // for (const auto & lidar_point : cluster_buff[i].data){ + // ClusterEdgePC->push_back(lidar_point.point); + // } + // } + + // // Publish edge points in large clusters + // LiDARTag::_publishPC(ClusterEdgePC, _pub_frame, string("clusteredgepc")); + if (_log_data) + fplanefit.close(); + } + + + /* + * A function to + * (1) do adaptive thresholding (Maximize and minimize intensity) by comparing + * with the average value and + * (2) sort points with ring number and re-index with current cluster into + * tag_edges vector so as to do regression boundary lines + * (3) It will *remove* if linefitting fails + */ + bool LiDARTag::_adaptiveThresholding(ClusterFamily_t &cluster){ + if (_debug_time) { + _timing.timing = std::chrono::steady_clock::now(); + } + _organizeDataPoints(cluster); + if (_debug_time) { + _timing.organize_points_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + if (!LiDARTag::_detectPayloadBoundries(cluster)){ + // removal has been done inside the function + if (_debug_time) { + _timing.line_fitting_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + } + return false; + } else { + // TODO: calculate the average of edge points + // substract the average from each edge point and calculate PCA + + + // _timing.line_fitting_time += utils::spendTime(clock(), _timing.timing); + // _timing.timing = clock(); + // _extractPayloadWOThreshold(cluster); + // _timing.payload_extraction_time += utils::spendTime(clock(), _timing.timing); + // 2 is because this payload points is actually includes black + // boundary + // if (cluster.payload.size() < _min_returns_per_grid*std::pow((std::sqrt(_tag_family)+2*_black_border), 2)) { + // //_debug_cluster.ExtractPayload.push_back(&cluster); + // _result_statistics.cluster_removal.minimum_return ++; + // return false; + // } + + // return true; + if (_debug_time) { + _timing.timing = std::chrono::steady_clock::now(); + } + _estimatePrincipleAxis(cluster); + // cout << "after PCA" << endl; + // for (int eigenpc_index = 0; eigenpc_index < cluster.merged_data.cols(); ++eigenpc_index){ + // if (isnan(cluster.merged_data(0, eigenpc_index)) || + // isnan(cluster.merged_data(1, eigenpc_index)) || + // isnan(cluster.merged_data(2, eigenpc_index)) || + // isnan(cluster.merged_data(3, eigenpc_index))) { + // std::cout << "eigenpc_index : " << + // eigenpc_index << std::endl; + // std::cout << "cluster merged : " << + // cluster.merged_data.col(eigenpc_index) << endl; + // } + // } + if (_debug_time) { + _timing.pca_time += utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + // Fit line of the cluster + if (!_transformSplitEdges(cluster)) { + _result_statistics.cluster_removal.line_fitting++; + _result_statistics.remaining_cluster_size--; + return false; + } + // cout << "after split edge poins" << endl; + // for (int eigenpc_index = 0; eigenpc_index < cluster.merged_data.cols(); ++eigenpc_index){ + // if (isnan(cluster.merged_data(0, eigenpc_index)) || + // isnan(cluster.merged_data(1, eigenpc_index)) || + // isnan(cluster.merged_data(2, eigenpc_index)) || + // isnan(cluster.merged_data(3, eigenpc_index))) { + // std::cout << "eigenpc_index : " << + // eigenpc_index << std::endl; + // std::cout << "cluster merged : " << + // cluster.merged_data.col(eigenpc_index) << endl; + // } + // } + if (_debug_time) { + _timing.split_edge_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + if (!_pose_optimization) { + cluster.pose_tag_to_lidar.homogeneous = + Eigen::Matrix4f::Identity(4, 4); + _storeTemplatePts(cluster); + + return true; + } else { + int status = _optimizePose(cluster); + if (status < 0) { + _result_statistics.cluster_removal.pose_optimization++; + _result_statistics.remaining_cluster_size--; + // cout << "about to return false after _optimizePose" << endl; + + return false; + } else { + if (_debug_time) { + _timing.pose_optimization_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + // cout << "about to store template points" << endl; + _storeTemplatePts(cluster); + if (_debug_time) { + _timing.store_template_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + + if (!_id_decoding){ + _assignClusterPose( + cluster.pose_tag_to_lidar, + cluster.pose, 0); + return true; + } else { + // cout << "about to deocde" << endl; + if (!LiDARTag::_decodePayload(cluster)){ + _result_statistics.cluster_removal.decoding_failure++; + _result_statistics.remaining_cluster_size--; + // cout << "about to return false after deocding" << endl; + return false; + } else { + if (_debug_time) { + _timing.payload_decoding_time += + utils::spendElapsedTimeMilli( + std::chrono::steady_clock::now(), _timing.timing); + _timing.timing = std::chrono::steady_clock::now(); + } + // cout << "about to assign pose" << endl; + _assignClusterPose( + cluster.pose_tag_to_lidar, + cluster.pose, + cluster.rkhs_decoding.rotation_angle); + return true; + } + } + } + } + // LiDARTag::_decodePayload(cluster); + // if (_debug_time) { + // _timing.payload_decoding_time += utils::spendTime(clock(), _timing.timing); + // _timing.timing = clock(); + // } + // _assignClusterPose( + // cluster.pose_tag_to_lidar, + // cluster.pose, + // cluster.rkhs_decoding.rotation_angle); + // return true; + // ROS_ERROR_STREAM("Decoding ID is not supported yet. Please change decode_id in the launch file to false. Currently is " << _id_decoding); + + // // under developement + // if (_debug_time) { + // _timing.timing = clock(); + // } + // + // if (LiDARTag::_decodePayload(cluster)){ + // if (_debug_time) { + // _timing.payload_decoding_time += utils::spendTime(clock(), _timing.timing); + // _timing.timing = clock(); + // } + + // _estimatePrincipleAxis(cluster); + // if (_debug_time) { + // _timing.normal_vector_time += utils::spendTime(clock(), _timing.timing); + // _timing.timing = clock(); + // } + + // LiDARTag::_tagToRobot(cluster.cluster_id, cluster.normal_vector, + // cluster.pose, cluster.transform, cluster.average); + // if (_debug_time) { + // _timing.tag_to_robot_time += utils::spendTime(clock(), _timing.timing); + // } + // + // return true; + // } + // else { + // return false; + // } + // } + // else { + // if (_debug_time) { + // _timing.timing = std::chrono::steady_clock::now(); + // } + // _estimatePrincipleAxis(cluster); + // if (_debug_time) { + // _timing.pca_time += + // utils::spendElapsedTimeMilli(std::chrono::steady_clock::now(), + // _timing.timing); + // _timing.timing = std::chrono::steady_clock::now(); + // } + // if (!_transformSplitEdges(cluster)) return false; + // if (_debug_time) { + // _timing.split_edge_time += + // utils::spendElapsedTimeMilli( + // std::chrono::steady_clock::now(), + // _timing.timing); + // _timing.timing = std::chrono::steady_clock::now(); + // } + // + // if (_optimizePose(cluster)) { + // if (_debug_time) { + // _timing.pose_optimization_time += + // utils::spendElapsedTimeMilli( + // std::chrono::steady_clock::now(), + // _timing.timing); + // _timing.timing = std::chrono::steady_clock::now(); + // } + // _storeTemplatePts(cluster); + // if (_debug_time) { + // _timing.store_template_time += + // utils::spendElapsedTimeMilli( + // std::chrono::steady_clock::now(), + // _timing.timing); + // } + // } else { + // return false; + // } + + // // under developement + // // LiDARTag::_decodePayload(cluster); + + // // // directly assign ID + // // string Code(_assign_id); + // // uint64_t Rcode = stoull(Code, nullptr, 2); + // // BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &cluster.entry); + // // cluster.cluster_id = cluster.entry.id; + + + // // // if (cluster.average.y > 0) cluster.cluster_id = 1; + // // // else cluster.cluster_id = 2; + + // // LiDARTag::_tagToRobot(cluster.cluster_id, cluster.normal_vector, + // // cluster.pose, cluster.transform, cluster.average); + // } + } + } + + + /* + * A function to assign the pose to the cluster using the results of + * L1-optimization and RKHS decoding results + */ + void LiDARTag::_assignClusterPose( + const Homogeneous_t &H_TL, + Homogeneous_t &H_LT, + const int &ang_num) { + float rotation_angle = -ang_num * 90; + Eigen::Vector3f trans_v = Eigen::Vector3f::Zero(3); + Eigen::Vector3f rot_v; + rot_v << rotation_angle, 0, 0; + Eigen::Matrix4f H = utils::computeTransformation(rot_v, trans_v); + + H_LT.homogeneous = (H * H_TL.homogeneous).inverse(); + H_LT.rotation = H_LT.homogeneous.topLeftCorner(3, 3); + H_LT.translation = H_LT.homogeneous.topRightCorner(3, 1); + Eigen::Vector3f euler = + H_LT.rotation.eulerAngles(0, 1, 2); // x,y,z convention + H_LT.roll = euler[0]; + H_LT.pitch = euler[1]; + H_LT.yaw = euler[2]; + // cout << "H_TL\n" << H_TL.homogeneous << endl; + // cout << "H\n" << H << endl; + // cout << "H_LT\n" << H_LT.homogeneous << endl; + // cout << "===" << endl; + } + + + /* + * A function to store transformed points + */ + void LiDARTag::_storeTemplatePts(ClusterFamily_t &cluster) { + cluster.rkhs_decoding.initial_template_points = + cluster.initial_pose.homogeneous * cluster.merged_data_h; + cluster.rkhs_decoding.initial_template_points.bottomRows(1) = + cluster.merged_data.bottomRows(1); + + cluster.rkhs_decoding.template_points = + cluster.pose_tag_to_lidar.homogeneous * cluster.merged_data_h; + cluster.rkhs_decoding.template_points.bottomRows(1) = + cluster.merged_data.bottomRows(1); + + + // cluster.rkhs_decoding.template_points.topRows(3) = + // cluster.merged_data.topRows(3); + + // cluster.rkhs_decoding.template_points = + // (cluster.initial_pose.homogeneous * + // cluster.rkhs_decoding.template_points).eval(); + + // cluster.rkhs_decoding.template_points.bottomRows(1) = + // cluster.merged_data.bottomRows(1); + + // cluster.rkhs_decoding.template_points_xyz = + // cluster.rkhs_decoding.template_points.topRows(3); + + // cluster.rkhs_decoding.template_points_feat = + // cluster.rkhs_decoding.template_points.bottomRows(1); + + + + // for (int i=0; ipoint.intensity << endl; + // } + // for (int i=0; ipoint.intensity << endl; + // } + } + + /* A function to publish pose of tag to the robot + */ + void LiDARTag::_tagToRobot( + const int &cluster_id, + const Eigen::Vector3f &normal_vec, + Homogeneous_t &pose, + tf::Transform &transform, const PointXYZRI &ave){ + Eigen::Vector3f x(1, 0, 0); + Eigen::Vector3f y(0, 1, 0); + Eigen::Vector3f z(0, 0, 1); + pose.rotation = utils::qToR(normal_vec).cast (); + pose.translation << ave.x, ave.y, ave.z; + + pose.yaw = utils::rad2Deg(acos(normal_vec.dot(y))); + pose.pitch = -utils::rad2Deg(acos(normal_vec.dot(x))); + pose.roll = utils::rad2Deg(acos(normal_vec.dot(z))); + + pose.homogeneous.topLeftCorner(3,3) = pose.rotation; + pose.homogeneous.topRightCorner(3,1) = pose.translation; + pose.homogeneous.row(3) << 0,0,0,1; + + static tf::TransformBroadcaster broadcaster_; + transform.setOrigin(tf::Vector3(ave.x, ave.y, ave.z)); + + // rotate to fit iamge frame + Eigen::Vector3f qr(0, std::sqrt(2)/2, 0); + float qr_w = std::sqrt(2)/2; + // Eigen::Vector3f qr(-0.5, 0.5, -0.5); + // float qr_w = 0.5; + + // Eigen::Vector3f qr(-0.5, -0.5, -0.5); + // float qr_w = 0.5; + // Eigen::Vector3f qr(std::sqrt(2)/2, 0, 0); + // float qr_w = std::sqrt(2)/2; + // Eigen::Vector3f qi_camera_frame = qr_w*normal_vec + 0*qr + qr.cross(normal_vec); // 0 is q.w of normalvec + // float qw_camera_frame = qr_w*0 - qr.dot(normal_vec); // 0 is q.w of normalvec + Eigen::Vector3f qi_camera_frame = + normal_vec + 2*qr_w*(qr.cross(normal_vec)) + 2*qr.cross(qr.cross(normal_vec)); // 0 is q.w of normalvec + float qw_camera_frame = 0; // 0 is q.w of normalvec + + + Eigen::Vector3f q_i = qi_camera_frame; + double q_w = qw_camera_frame; + double norm = + std::sqrt(std::pow(q_i(0), 2) + + std::pow(q_i(1), 2) + + std::pow(q_i(2), 2) + + std::pow(q_w, 2)); + q_i = (q_i/norm).eval(); + q_w = q_w/norm; + tf::Quaternion q(q_i(0), q_i(1), q_i(2), q_w); + transform.setRotation(q); + broadcaster_.sendTransform( + tf::StampedTransform(transform, + _point_cloud_header.stamp, + _pub_frame, + to_string(cluster_id)+"_rotated")); + + + tf::Quaternion q2(normal_vec(0), normal_vec(1), normal_vec(2), 0); + transform.setRotation(q2); + broadcaster_.sendTransform( + tf::StampedTransform( + transform, + _point_cloud_header.stamp, + _pub_frame, + "LiDARTag-ID" + to_string(cluster_id))); + + // publish lidar tag pose + lidartag_msgs::LiDARTagDetection lidartag_msg; //single message + lidartag_msg.id = cluster_id; + lidartag_msg.size = _payload_size; + geometry_msgs::Quaternion geo_q; + geo_q.x = q_i(0); + geo_q.y = q_i(1); + geo_q.z = q_i(2); + geo_q.w = q_w; + // cout << "R: \n" << pose.rotation << endl; + // cout << "det(R): \n" << pose.rotation.determinant() << endl; + // cout << "q: " << q_i(0) << ", " + // << q_i(1) << ", " + // << q_i(2) << ", " + // << q_w << endl; + lidartag_msg.pose.position.x = ave.x; + lidartag_msg.pose.position.y = ave.y; + lidartag_msg.pose.position.z = ave.z; + lidartag_msg.pose.orientation = geo_q; + lidartag_msg.header = _point_cloud_header; + lidartag_msg.header.frame_id = + std::string("lidartag_") + to_string(cluster_id); + lidartag_msg.frame_index = _point_cloud_header.seq; + _lidartag_pose_array.header = _point_cloud_header; + _lidartag_pose_array.frame_index = _point_cloud_header.seq; + _lidartag_pose_array.detections.push_back(lidartag_msg); + // cout << "R.T*NV: " << endl << pose.rotation.transpose()*normal_vec << endl; + // cout << "H: " << endl << pose.homogeneous << endl; + + /* + Eigen::Vector3f x(1, 0, 0); + Eigen::Vector3f y(0, 1, 0); + Eigen::Vector3f z(0, 0, 1); + Eigen::Matrix3f zSkew; + zSkew << 0, -z(2), z(1), + z(2), 0, -z(0), + -z(1), z(0), 0; + Eigen::Vector3f u = zSkew*normal_vec; + //u = x.cross(normal_vec); + //u = z.cross(normal_vec); + //u = -z.cross(normal_vec); + //u = -x.cross(normal_vec); + //u = -y.cross(normal_vec); + //u = x.cross(normal_vec); + u = (u.normalized()).eval(); + float theta = acos(z.dot(normal_vec)); + u = (u*theta).eval(); + Eigen::Matrix3f uSkew; + uSkew << 0, -u(2), u(1), + u(2), 0, -u(0), + -u(1), u(0), 0; + pose.rotation = uSkew.exp(); + pose.translation << ave.x, ave.y, ave.z; + pose.yaw = utils::rad2Deg(acos(normal_vec.dot(y))); + pose.pitch = -utils::rad2Deg(acos(normal_vec.dot(x))); + pose.roll = utils::rad2Deg(acos(normal_vec.dot(z))); + pose.homogeneous.topLeftCorner(3,3) = pose.rotation; + pose.homogeneous.topRightCorner(3,1) = pose.translation; + pose.homogeneous.row(3) << 0,0,0,1; + static tf::TransformBroadcaster broadcaster_; transform.setOrigin(tf::Vector3(ave.x, ave.y, ave.z)); + Eigen::Vector3f q_i = sin(theta/2)*u; + double q_w = std::cos(theta/2); + double norm = std::sqrt(std::pow(q_i(0), 2) + std::pow(q_i(1), 2) + std::pow(q_i(2), 2) + std::pow(q_w, 2)); + q_i = (q_i/norm).eval(); + q_w = q_w/norm; + tf::Quaternion q(q_i(0), q_i(1), q_i(2), q_w); + transform.setRotation(q); + broadcaster_.sendTransform(tf::StampedTransform(transform, _point_cloud_header.stamp, + _pub_frame, to_string(cluster_id))); + // publish lidar tag pose + lidartag_msgs::LiDARTagDetection lidartag_msg; //single message + lidartag_msg.id = cluster_id; + lidartag_msg.size = _payload_size; + geometry_msgs::Quaternion geo_q; + geo_q.x = q_i(0); + geo_q.y = q_i(1); + geo_q.z = q_i(2); + geo_q.w = q_w; + // cout << "R: \n" << pose.rotation << endl; + // cout << "det(R): \n" << pose.rotation.determinant() << endl; + // cout << "q: " << q_i(0) << ", " + // << q_i(1) << ", " + // << q_i(2) << ", " + // << q_w << endl; + lidartag_msg.pose.position.x = ave.x; + lidartag_msg.pose.position.y = ave.y; + lidartag_msg.pose.position.z = ave.z; + lidartag_msg.pose.orientation = geo_q; + lidartag_msg.header = _point_cloud_header; + lidartag_msg.header.frame_id = std::string("lidartag_") + to_string(cluster_id); + _lidartag_pose_array.header = _point_cloud_header; + _lidartag_pose_array.detections.push_back(lidartag_msg); + // cout << "R.T*NV: " << endl << pose.rotation.transpose()*normal_vec << endl; + // cout << "H: " << endl << pose.homogeneous << endl; + */ + } + + /* + * 1. Convert datatype from PCL to Eigen type for pose optimization. + * 2. Merge edge points and data points into merged_data and merged_data_h. + * 3. Compute mean of the cluster, including the mean of intensity + * 4. Organize "data" points only for boundry detection. When detecting + * boundaries, we don't care about PoI. + */ + void LiDARTag::_organizeDataPoints(ClusterFamily_t &cluster){ + cluster.ordered_points_ptr.resize(_beam_num); + + cluster.merged_data.resize(4, cluster.inliers); + cluster.merged_data_h.resize(4, cluster.inliers); + int eigenpc_index = 0; + Eigen::Vector4f cur_vec; + float x_mean = 0; + float y_mean = 0; + float z_mean = 0; + float i_mean = 0; + for (int i = 0; i < cluster.edge_points.size(); ++i){ + if (cluster.edge_points[i].valid != 1) + continue; + _PointXYZRIToEigenVector(cluster.edge_points[i].point, cur_vec); + cluster.merged_data.col(eigenpc_index) = cur_vec; + cluster.merged_data_h.col(eigenpc_index) << + cur_vec(0), cur_vec(1), cur_vec(2), 1; + x_mean += cur_vec[0]; + y_mean += cur_vec[1]; + z_mean += cur_vec[2]; + i_mean += cur_vec[3]; + eigenpc_index +=1; + + + // LiDARPoints_t* ClusterPointPtr = &cluster.edge_points[i]; + // ClusterPointPtr->point.intensity = + // cluster.edge_points[i].point.intensity / + // cluster.max_intensity.intensity; + // cluster.ordered_points_ptr[ + // ClusterPointPtr->point.ring].push_back(ClusterPointPtr); + + // if (isnan(cluster.merged_data(0, eigenpc_index)) || + // isnan(cluster.merged_data(1, eigenpc_index)) || + // isnan(cluster.merged_data(2, eigenpc_index)) || + // isnan(cluster.merged_data(3, eigenpc_index))) { + // std::cout << "vector : " << cur_vec << std::endl; + // std::cout << "edge points : " << endl; + // utils::COUT(cluster.edge_points[i].point); + // std::cout << "eigenpc_index : " << eigenpc_index << std::endl; + // } + } + for (int i=0; i < cluster.data.size(); ++i){ + if (cluster.data[i].valid != 1) + continue; + _PointXYZRIToEigenVector(cluster.data[i].point, cur_vec); + cluster.merged_data.col(eigenpc_index) = cur_vec; + cluster.merged_data_h.col(eigenpc_index) << + cur_vec(0), cur_vec(1), cur_vec(2), 1; + x_mean += cur_vec[0]; + y_mean += cur_vec[1]; + z_mean += cur_vec[2]; + i_mean += cur_vec[3]; + eigenpc_index +=1; + + + LiDARPoints_t* ClusterPointPtr = &cluster.data[i]; + // ClusterPointPtr->point.intensity = + // cluster.data[i].point.intensity / + // cluster.max_intensity.intensity; + cluster.ordered_points_ptr[ + ClusterPointPtr->point.ring].push_back(ClusterPointPtr); + + // if (isnan(cluster.merged_data(0, eigenpc_index)) || + // isnan(cluster.merged_data(1, eigenpc_index)) || + // isnan(cluster.merged_data(2, eigenpc_index)) || + // isnan(cluster.merged_data(3, eigenpc_index))) { + // std::cout << "vector : " << cur_vec << std::endl; + // std::cout << "edge points : " << std::endl; + // utils::COUT(cluster.data[i].point); + // std::cout << "eigenpc_index : " << eigenpc_index << std::endl; + // } + } + // if (eigenpc_index != cluster.inliers) { + // cout << "======================" << endl; + // cout << "number is wrong" << endl; + // } + cluster.average.x = x_mean / cluster.inliers; + cluster.average.y = y_mean / cluster.inliers; + cluster.average.z = z_mean / cluster.inliers; + cluster.average.intensity = i_mean / cluster.inliers; + cluster.rkhs_decoding.num_points = cluster.inliers; + cluster.rkhs_decoding.ave_intensity = cluster.average.intensity; + + for (int ring = 0; ring < _beam_num; ++ring){ + sort(cluster.ordered_points_ptr[ring].begin(), + cluster.ordered_points_ptr[ring].end(), + utils::compareIndex); + } + + // cluster.average.x = cluster.merged_data.row(0).mean(); + // cluster.average.y = cluster.merged_data.row(1).mean(); + // cluster.average.z = cluster.merged_data.row(2).mean(); + // cluster.average.intensity = cluster.merged_data.row(3).mean(); + + + // cout << "Ave1:" << cluster.average.x << ", "<< cluster.average.y + // << ", "<< cluster.average.z << endl; + + + + // PointXYZRI average{0,0,0,0}; + // for (int k = 0; k < cluster.edge_points.size(); ++k) { + // if (cluster.edge_points[k].valid != 1) continue; + // average.x += cluster.edge_points[k].point.x; + // average.y += cluster.edge_points[k].point.y; + // average.z += cluster.edge_points[k].point.z; + // average.intensity += cluster.edge_points[k].point.intensity; + // } + // for (int k = 0; k < cluster.data.size(); ++k) { + // if (cluster.data[k].valid != 1) continue; + // average.x += cluster.data[k].point.x; + // average.y += cluster.data[k].point.y; + // average.z += cluster.data[k].point.z; + // average.intensity += cluster.data[k].point.intensity; + // } + // cluster.average.x = average.x/ cluster.inliers; + // cluster.average.y = average.y/ cluster.inliers; + // cluster.average.z = average.z/ cluster.inliers; + // cluster.average.intensity = average.intensity/ cluster.inliers; + + // cout << "Ave2:" << cluster.average.x << ", "<< cluster.average.y + // << ", "<< cluster.average.z << endl; + } + + + /* + * A function to extract the payload points from a valid cluster. + * Let's say we have 10 points on the left boundary (line) of the tag and 9 points on the right boundary + * (line) of the tag. + * It is seperated into two parts. + * TODO: should use medium instead of max points + * (i) Find the max points that we have on a ring in this cluster by + * exmaming the average points on the first 1/2 rings int((10+9)/4) + * (ii) For another half of the rings, we just find the start index and add the + * average number of points to the payload points + */ + void LiDARTag::_extractPayloadWOThreshold(ClusterFamily_t &cluster){ + int last_round_length = 0; // Save to recover a missing ring + PointXYZRI average{0,0,0,0}; + for(int ring=0; ring<_beam_num; ++ring){ + + // if (cluster.payload_right_boundary_ptr[ring]!=0) + // cluster.payload_boundary_ptr.push_back(cluster.payload_right_boundary_ptr[ring]); + + // if (cluster.payload_left_boundary_ptr[ring]!=0) + // cluster.payload_boundary_ptr.push_back(cluster.payload_left_boundary_ptr[ring]); + + if (cluster.payload_right_boundary_ptr[ring]==0 && + cluster.payload_left_boundary_ptr[ring]==0) continue; + // cout << "ring" << ring << endl; + else if (cluster.payload_right_boundary_ptr[ring]!=0 && + cluster.payload_left_boundary_ptr[ring]!=0){ + cluster.payload_boundary_ptr.push_back(cluster.payload_right_boundary_ptr[ring]); + cluster.payload_boundary_ptr.push_back(cluster.payload_left_boundary_ptr[ring]); + int StartIndex = cluster.payload_left_boundary_ptr[ring]->index; + int EndIndex = cluster.payload_right_boundary_ptr[ring]->index; + last_round_length = EndIndex - StartIndex; + + + for (int j=0; jindex == StartIndex){ + // Remove index itself because itself is not the part of a + // payload + for (int k=j+1; k=cluster.ordered_points_ptr[ring].size()) break; // make sure the index is valid + // cout << "j: " << j << endl; + // cout << "k: " << k << endl; + // cout << "validation1: " << endl; + // utils::COUT(cluster.ordered_points_ptr[ring][k]->point); + // + cluster.payload.push_back(cluster.ordered_points_ptr[ring][k]); + average.x += cluster.ordered_points_ptr[ring][k]->point.x; + average.y += cluster.ordered_points_ptr[ring][k]->point.y; + average.z += cluster.ordered_points_ptr[ring][k]->point.z; + } + break; + } + } + } + cluster.average.x = average.x/ cluster.payload.size(); + cluster.average.y = average.y/ cluster.payload.size(); + cluster.average.z = average.z/ cluster.payload.size(); + // else if (last_round_length!=0 && cluster.payload_right_boundary_ptr[ring]!=0){ + // int EndIndex = cluster.payload_right_boundary_ptr[ring]->index; + + // for (int j=cluster.ordered_points_ptr[ring].size()-1; j>0; --j){ + // if (cluster.ordered_points_ptr[ring][j]->index == EndIndex){ + // cluster.payload.push_back(cluster.ordered_points_ptr[ring][j]); + + // for (int k=j-1; k>j-last_round_length; --k){ + // if (k<0) break; // make sure the index is valid + // cluster.payload.push_back(cluster.ordered_points_ptr[ring][k]); + // } + // break; + // } + // } + + // } + // else if (last_round_length!=0 && cluster.payload_left_boundary_ptr[ring]!=0){ + // int StartIndex = cluster.payload_left_boundary_ptr[ring]->index; + + // for (int j=0; jindex == StartIndex){ + // cluster.payload.push_back(cluster.ordered_points_ptr[ring][j]); + + // for (int k=j-1; k=cluster.ordered_points_ptr[ring].size()) break; // make sure the index is valid + // cluster.payload.push_back(cluster.ordered_points_ptr[ring][k]); + // } + // break; + // } + // } + + // } + } + } + + + /* + * Compare current point's gradient intensity with next points + * gradient intensity + * Example: + * o: white, x: black + * + * a9876543210 + * ooooxxxxxxxooooo + * ^^^^ ^^^^ + * |||| |||| + * Gradient from 1-2 sould be large; the same as the gradient from 0-2 + * Gradient from 9-8 sould be large; the same as the gradient from a-8 + * + * [Note] + * 1. At least two points have to be on the white boundaries. + * 2. Therefore, five points on a ring is required to be counted as a + * boundary point. + * The extreme case: + * Two white points on each side. + * ooxoo + */ + bool LiDARTag::_detectPayloadBoundries(ClusterFamily_t &cluster){ + cluster.payload_right_boundary_ptr.resize(_beam_num); + cluster.payload_left_boundary_ptr.resize(_beam_num); + bool boundary_flag = true; + bool ring_point_flag = true; + + // Initialization + cluster.tag_edges.upper_ring = _beam_num; + cluster.tag_edges.lower_ring = 0; + + double detection_threshold = _payload_intensity_threshold * + cluster.average.intensity/ 2; + // double detection_threshold = + // (cluster.average.intensity - cluster.min_intensity.intensity)/ + // (_payload_intensity_threshold*cluster.max_intensity.intensity); + + int boundary_piont_count = 0; // Check there're sufficient points + int num_valid_rings = 0; + + bool found_right_ring_boundary; + bool found_left_ring_boundary; + + // a ring should at least have three points to have intensity gradients + // from left to right and from right to right + int minimum_ring_points = 5; + + for (int ring = 0; ring < _beam_num; ++ring){ + found_right_ring_boundary = false; + found_left_ring_boundary = false; + + if (cluster.ordered_points_ptr[ring].size() < minimum_ring_points) { + continue; + } + + // [Left] + // Find edges from the left of a ring + // Start from 1 becasue we take another point on the left into account + // size -1 because we compare with next point + for (int P = 1; + P < ceil((cluster.ordered_points_ptr[ring].size() - 1) / 2); + ++P){ + + // (1) By knowing it from white to black on the left calucate the + // intensity gradient + // (2) Since have thresholded already, we could also choose > 255 + // (3) To determin if p if the edge: + // 1. compare with p+1 (to its right) + + if ((cluster.ordered_points_ptr[ring][P]->point.intensity - + cluster.ordered_points_ptr[ring][P+1]-> + point.intensity > detection_threshold) + && (cluster.ordered_points_ptr[ring][P-1]->point.intensity - + cluster.ordered_points_ptr[ring][P+1]-> + point.intensity>detection_threshold)) { + // if ((cluster.ordered_points_ptr[ring][P]->point.intensity - + // cluster.ordered_points_ptr[ring][P+1]->point.intensity > + // detection_threshold)) { + cluster.payload_left_boundary_ptr[ring] = + cluster.ordered_points_ptr[ring][P]; + boundary_piont_count ++; + found_left_ring_boundary = true; + break; + } + } + + // [Right] + // Find edges from the right a ring + // -1-2: -1 of index and another -2 is becasue we take into account another two points on the right + // -1 : because we compare with left point + for (int P = cluster.ordered_points_ptr[ring].size() - 2; + P > floor((cluster.ordered_points_ptr[ring].size() - 1) / 2); + --P){ + + // (1) By knowing it from white to black on the left to calucate the + // intensity gradient + // (2) Since have thresholded already, we could also choose > 255 + // cluster.payload_right_boundary_ptr[ring] = cluster.ordered_points_ptr[ring][P]; + if ((cluster.ordered_points_ptr[ring][P]->point.intensity - + cluster.ordered_points_ptr[ring][P-1]->point.intensity > + detection_threshold) && + (cluster.ordered_points_ptr[ring][P+1]->point.intensity - + cluster.ordered_points_ptr[ring][P-1]->point.intensity > + detection_threshold)) { + // if ((cluster.ordered_points_ptr[ring][P]->point.intensity - + // cluster.ordered_points_ptr[ring][P-1]->point.intensity > + // detection_threshold)) { + + cluster.payload_right_boundary_ptr[ring] = + cluster.ordered_points_ptr[ring][P]; + boundary_piont_count ++; + found_right_ring_boundary = true; + + break; + } + } + + + if (found_left_ring_boundary && found_right_ring_boundary) { + num_valid_rings++; + } + } + cluster.boundary_pts = boundary_piont_count; + cluster.boundary_rings = num_valid_rings; + + // reject if points are too less (can't even get decoded!) + // if (boundary_piont_count < int(sqrt(_tag_family))*2 || + // num_valid_rings < int(sqrt(_tag_family))) { + if (boundary_piont_count < int(sqrt(_tag_family))*2) { + _result_statistics.cluster_removal.boundary_point_check++; + _result_statistics.remaining_cluster_size--; + boundary_flag = false; + } else if (num_valid_rings < std::min( + int(sqrt(_tag_family)), _minimum_ring_boundary_points)) { + _result_statistics.cluster_removal.minimum_ring_points++; + _result_statistics.remaining_cluster_size--; + ring_point_flag = false; + } + + if (_debug_info) { + ROS_DEBUG_STREAM("==== _detectPayloadBoundries ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + ROS_DEBUG_STREAM("Boundary threshold : " << detection_threshold); + ROS_DEBUG_STREAM("Boundary_piont_count : " << boundary_piont_count); + ROS_DEBUG_STREAM("Num_valid_rings: " << num_valid_rings); + ROS_DEBUG_STREAM("Status: " << boundary_flag && ring_point_flag); + } + + + return boundary_flag && ring_point_flag; + } + + Homogeneous_t + LiDARTag::_estimatePose(ClusterFamily_t &cluster){ + Homogeneous_t pose; + //translation min sign + pose.translation << -cluster.average.x, -cluster.average.y, -cluster.average.z; + + + //rotation// + Eigen::Vector3f x_axis(1,0,0); + Eigen::Vector3f edge_direction(0,0,1); + Eigen::Vector3f base_vector1 = utils::cross_product(x_axis, edge_direction); + + Eigen::Vector3f normal_vector = cluster.normal_vector; + Eigen::Vector3f edge_vector = _estimateEdgeVector(cluster); + Eigen::Vector3f base_vector2 = utils::cross_product(normal_vector, edge_vector); + + + + Eigen::Matrix3f V, W; + V.col(0) = normal_vector; + V.col(1) = edge_vector; + V.col(2) = base_vector2; + W.col(0) = x_axis; + W.col(1) = edge_direction; + W.col(2) = base_vector1; + + pose.rotation = W * V.transpose(); + + // float cos_theta = utils::dot_product(x_axis, normal_vector); + // float rotation_angle = std::acos(cos_theta); + // Eigen::Vector3f rotation_axis = utils::cross_product(normal_vector, x_axis); + // Eigen::AngleAxisf rotation_vector (rotation_angle, rotation_axis); + + // pose.rotation = rotation_vector.toRotationMatrix(); + + + //euler angles + Eigen::Vector3f euler_angles = pose.rotation.eulerAngles(2,1,0); + pose.roll = euler_angles[2]; + pose.pitch = euler_angles[1]; + pose.yaw = euler_angles[0]; + // + pose.homogeneous.topLeftCorner(3,3) = pose.rotation; + pose.homogeneous.topRightCorner(3,1) = pose.translation; + pose.homogeneous.row(3) << 0,0,0,1; + if (_debug_info) { + std::cout << "=============================================================" << std::endl; + std::cout << "estimate euler angle: \n" << pose.roll*180/M_PI <<" "<< pose.pitch*180/M_PI <<" "<< pose.yaw*180/M_PI << std::endl; + std::cout << "estimate transformation: \n" << pose.homogeneous << std::endl; + } + + + return pose; + + } + + Eigen::Vector3f LiDARTag::_estimateEdgeVector(ClusterFamily_t &cluster){ + if (_debug_info) { + ROS_DEBUG_STREAM("==== _estimateEdgeVector ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + } + + pcl::PointCloud::Ptr cloud(new pcl::PointCloud); + // cloud->points.resize(_beam_num); + for (std::size_t i = 0; i < _beam_num; ++i) { + if(!cluster.payload_left_boundary_ptr[i]) continue; + pcl::PointXYZ p(cluster.payload_left_boundary_ptr[i]->point.x,cluster.payload_left_boundary_ptr[i]->point.y,cluster.payload_left_boundary_ptr[i]->point.z); + cloud->points.push_back(p); + } + if (_debug_info) { + ROS_DEBUG_STREAM("Cloud points: " << cloud->points.size()); + } + + pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); + pcl::PointIndices::Ptr inliers (new pcl::PointIndices); + pcl::SACSegmentation seg; + + seg.setOptimizeCoefficients (true); + seg.setModelType(pcl::SACMODEL_LINE); + seg.setMethodType(pcl::SAC_RANSAC); + seg.setDistanceThreshold(0.02); + + seg.setInputCloud(cloud); + seg.segment(*inliers, *coefficients); + if (_debug_info) { + ROS_DEBUG_STREAM("Inliers size " << inliers->indices.size ()); + } + + if (inliers->indices.size () == 0) + { + if (_debug_info) { + ROS_WARN_STREAM("Could not estimate a LINE model for the given dataset."); + } + } + + Eigen::Vector3f edge_vector(coefficients->values[3], coefficients->values[4], coefficients->values[5]); + edge_vector.normalize(); + if(edge_vector(2) < 0) edge_vector = -edge_vector; + if (_debug_info) { + ROS_DEBUG_STREAM("Edge vector: " << edge_vector.transpose()); + } + + _visualizeVector(edge_vector, cluster.average, 0); + return edge_vector; + } + + + + /* [Edge points and principal axes] + * A function to transform the edge points to the tag frame and split into 4 groups + * for each group of points, do line fitting and get four corner points from intersection of lines + * estimate the tagsize according to the mean of distance between consecutive two corner points + * get the initial pose by associating four corner points with the corners of template + * TODO: make this modular + */ + bool LiDARTag::_transformSplitEdges(ClusterFamily_t &cluster){ + pcl::PointCloud::Ptr cloud1(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud2(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud3(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud4(new pcl::PointCloud); + + pcl::PointCloud::Ptr TransformedPC(new pcl::PointCloud); + TransformedPC->reserve(_point_cloud_size); + TransformedPC->clear(); + + pcl::PointCloud::Ptr TransformedPCTag(new pcl::PointCloud); + TransformedPCTag->reserve(_point_cloud_size); + TransformedPCTag->clear(); + + + //separate edge points into 4 groups + for (int i=0; i transform_matrix = + cluster.principal_axes; + + transform_matrix = (transform_matrix.transpose()).eval(); + + Eigen::Vector3f transformed_edge_point = transform_matrix * edge_point; + + pcl::PointXYZ p; + p.x = transformed_edge_point(0); + p.y = transformed_edge_point(1); + p.z = 0; + LiDARPoints_t group_point; + group_point.point = cluster.edge_points[i].point; + if (transformed_edge_point(0) > 0) { + if (transformed_edge_point(1) > 0) { + cloud1->points.push_back(p); + group_point.point.intensity = 0; + cluster.edge_group1.push_back(group_point); + } else { + cloud2->points.push_back(p); + group_point.point.intensity = 85; + cluster.edge_group2.push_back(group_point); + } + } else { + if (transformed_edge_point(1) > 0) { + cloud4->points.push_back(p); + group_point.point.intensity = 170; + cluster.edge_group4.push_back(group_point); + } else { + cloud3->points.push_back(p); + group_point.point.intensity = 255; + cluster.edge_group3.push_back(group_point); + } + } + } + if (_debug_info) { + ROS_DEBUG_STREAM("==== _transformSplitEdges ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + } + + int num_edge_points = 3; + if (cloud1->size() < num_edge_points || + cloud2->size() < num_edge_points || + cloud3->size() < num_edge_points || + cloud4->size() < num_edge_points) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + return false; + } + + // //visualize all transformed points + // LiDARTag::_publishPC(TransformedPC, _pub_frame, string("transpts")); + + //To do: function this part + //get fitted line for points on the 1th side of the tag + Eigen::Vector4f line1; + Eigen::Vector4f line2; + Eigen::Vector4f line3; + Eigen::Vector4f line4; + if (!LiDARTag::_getLines(cloud1, line1)) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + + return false; + } + if (!LiDARTag::_getLines(cloud2, line2)) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + + return false; + } + if (!LiDARTag::_getLines(cloud3, line3)) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + + return false; + } + if (!LiDARTag::_getLines(cloud4, line4)) { + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << false); + + return false; + } + + // get intersections of four sides + Eigen::Vector3f intersection1 = _getintersec(line1, line2); + Eigen::Vector3f intersection2 = _getintersec(line2, line3); + Eigen::Vector3f intersection3 = _getintersec(line3, line4); + Eigen::Vector3f intersection4 = _getintersec(line1, line4); + + if (!_estimateTargetSize(cluster, + intersection1, intersection2, intersection3, intersection4)) + return false; + + // associate four intersections with four coners of the template + Eigen::MatrixXf payload_vertices(3, 4); + payload_vertices.col(0) = cluster.principal_axes * intersection1; + payload_vertices.col(1) = cluster.principal_axes * intersection2; + payload_vertices.col(2) = cluster.principal_axes * intersection3; + payload_vertices.col(3) = cluster.principal_axes * intersection4; + Eigen::MatrixXf ordered_payload_vertices = _getOrderedCorners(payload_vertices, cluster); + Eigen:: MatrixXf Vertices = Eigen::MatrixXf::Zero(3,5); + utils::formGrid(Vertices, 0, 0, 0, cluster.tag_size); + Eigen::Matrix3f R; + utils::fitGrid_new(Vertices, R, ordered_payload_vertices); + + // used for visualization for corner points + PointXYZRI showpoint; + PointXYZRI showpoint_tag; + for (int i = 0; i < 3; ++i) { + showpoint.intensity = 50; + showpoint.x = ordered_payload_vertices.col(i)(0); + showpoint.y = ordered_payload_vertices.col(i)(1); + showpoint.z = ordered_payload_vertices.col(i)(2); + + showpoint_tag.x = showpoint.x + cluster.average.x; + showpoint_tag.y = showpoint.y + cluster.average.y; + showpoint_tag.z = showpoint.z + cluster.average.z; + TransformedPC->push_back(showpoint); + TransformedPCTag->push_back(showpoint_tag); + } + if (!_debug_info) { + showpoint.intensity = 50; + showpoint.x = ordered_payload_vertices.col(3)(0); + showpoint.y = ordered_payload_vertices.col(3)(1); + showpoint.z = ordered_payload_vertices.col(3)(2); + + showpoint_tag.x = showpoint.x + cluster.average.x; + showpoint_tag.y = showpoint.y + cluster.average.y; + showpoint_tag.z = showpoint.z + cluster.average.z; + TransformedPC->push_back(showpoint); + TransformedPCTag->push_back(showpoint_tag); + } + LiDARTag::_publishPC(TransformedPC, _pub_frame, string("transpts")); + LiDARTag::_publishPC(TransformedPCTag, _pub_frame, string("transptstag")); + + // save initial lidar to tag pose matrix + cluster.initial_pose.rotation = R; + cluster.initial_pose.translation << -cluster.average.x, -cluster.average.y, -cluster.average.z; + cluster.initial_pose.translation = R * cluster.initial_pose.translation; + Eigen::Vector3f euler_angles = cluster.initial_pose.rotation.eulerAngles(0,1,2); + cluster.initial_pose.roll = euler_angles[0]; + cluster.initial_pose.pitch = euler_angles[1]; + cluster.initial_pose.yaw = euler_angles[2]; + cluster.initial_pose.homogeneous.topLeftCorner(3,3) = cluster.initial_pose.rotation; + cluster.initial_pose.homogeneous.topRightCorner(3,1) = cluster.initial_pose.translation; + cluster.initial_pose.homogeneous.row(3) << 0,0,0,1; + if (_debug_info) { + ROS_DEBUG_STREAM("Initial rotation matrix: \n" << R); + ROS_DEBUG_STREAM("Status: " << true); + } + + return true; + } + + + /* [Grouped edge points] + * A function to line fitting 4 lines of the tag + */ + bool LiDARTag::_getLines(pcl::PointCloud::Ptr cloud, Eigen::Vector4f &line){ + + pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients); + pcl::PointIndices::Ptr inliers (new pcl::PointIndices); + pcl::SACSegmentation seg; + + seg.setOptimizeCoefficients (true); + seg.setModelType(pcl::SACMODEL_LINE); + seg.setMethodType(pcl::SAC_RANSAC); + seg.setDistanceThreshold(0.02); + + seg.setInputCloud(cloud); + seg.segment(*inliers, *coefficients); + if (_debug_info) { + ROS_DEBUG_STREAM("Inliers size: " << inliers->indices.size()); + } + if (inliers->indices.size () == 0){ + if (_debug_info) { + ROS_WARN_STREAM("PCL: Could not estimate a LINE model for this cluster"); + PCL_ERROR ("Could not estimate a LINE model for the given dataset."); + } + return false; + } + line << coefficients->values[0], coefficients->values[1], coefficients->values[3], coefficients->values[4]; + return true; + } + + /* [Unordered corner points] + * A function to reorder the undered corner points from PCA + */ + Eigen::MatrixXf LiDARTag::_getOrderedCorners(Eigen::MatrixXf &payload_vertices, ClusterFamily_t &cluster) { + double max_z = payload_vertices.col(0)(2); + int index_max_z= 0; + for (int i = 0; i < 4; ++i) { + if (payload_vertices.col(i)(2) >= max_z) { + max_z = payload_vertices.col(i)(2); + index_max_z = i; + } + } + Eigen::Vector3f top(payload_vertices.col(index_max_z)(0), payload_vertices.col(index_max_z)(1), payload_vertices.col(index_max_z)(2)); + int next_index = index_max_z + 1; + if (next_index > 3) { + next_index = next_index - 4; + } + Eigen::Vector3f next(payload_vertices.col(next_index)(0), payload_vertices.col(next_index)(1), payload_vertices.col(next_index)(2)); + Eigen::Vector3f cross_vector = top.cross(next); + Eigen::Vector3f to_center(payload_vertices.row(0).mean() + cluster.average.x, payload_vertices.row(1).mean() + cluster.average.y, payload_vertices.row(2).mean() + cluster.average.z); + double direction = cross_vector.dot(to_center); + Eigen::MatrixXf output(3, 4); + int output_index; + int order; + if (direction > 0) { + order = 1; + } else { + order = -1; + } + for (int j = 0; j < 4; ++j) { + output_index = index_max_z + j * order; + if (output_index >= 4 || output_index < 0) { + output_index = output_index - 4 * order; + } + output.col(j) = payload_vertices.col(output_index); + } + return output; + } + /* [four corner points] + * A function to compute tag size according to the corner points of the tag + * [Note] The given four points are assumed in either cw or ccw. + * TODO: can be faster using std::lower_bound + */ + bool LiDARTag::_estimateTargetSize( + ClusterFamily_t &cluster, + const Eigen::Vector3f &point1, + const Eigen::Vector3f &point2, + const Eigen::Vector3f &point3, + const Eigen::Vector3f &point4) { + double distance1 = (point1 - point2).norm(); + double distance2 = (point2 - point3).norm(); + double distance3 = (point3 - point4).norm(); + double distance4 = (point4 - point1).norm(); + double mean_distance = + (distance1 + distance2 + distance3 + distance4) / 4; + double gap = 1e5; + double gap_temp; + double tagsize; + int size_num = 0; + bool status = true; + for (int i = 0; i < _tag_size_list.size(); ++i) { + gap_temp = abs(mean_distance - _tag_size_list[i]); + if (gap_temp < gap) { + gap = gap_temp; + tagsize = _tag_size_list[i]; + size_num = i; + } + } + + // float tagsize_tunable = 1.5; + if (gap > _tagsize_tunable * tagsize) { + // if (gap > 10) { + status = false; + } else { + cluster.tag_size = tagsize; + cluster.rkhs_decoding.size_num = size_num;; + status = true; + } + + // TODO: set a threshold to invalid the tagsize + if (_debug_info) { + ROS_DEBUG_STREAM("==== _estimateTargetSize ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + + cluster.edge_points.size()); + ROS_DEBUG_STREAM("Estimated side1 legth: " << distance1); + ROS_DEBUG_STREAM("Estimated side2 legth: " << distance2); + ROS_DEBUG_STREAM("Estimated side3 legth: " << distance3); + ROS_DEBUG_STREAM("Estimated side4 legth: " << distance4); + ROS_DEBUG_STREAM("Estimated size: " << mean_distance); + ROS_DEBUG_STREAM("Chosen size: " << tagsize); + ROS_DEBUG_STREAM("Gap : " << gap); + if (gap > _tagsize_tunable * tagsize) + ROS_DEBUG_STREAM("Status: " << status); + else + ROS_DEBUG_STREAM("Status: " << status); + } + + return status; + } + /* [two lines] + * A function to compute the intersection of two lines + */ + Eigen::Vector3f LiDARTag::_getintersec(Eigen::Vector4f line1, Eigen::Vector4f line2) { + + float c = line1(0); + float d = line1(1); + float a = line1(2); + float b = line1(3); + float p = line2(0); + float q = line2(1); + float m = line2(2); + float n = line2(3); + assert((a*n - b*m)!=0); + float x = (a*n*p-a*m*q+a*d*m-b*c*m) / (a*n - b*m); + float y = (b*n*p-b*c*n+a*d*n-b*m*q) / (a*n - b*m); + Eigen::Vector3f intersection(x,y,0); + return intersection; + } + + /* + * A function to estimate a cluster's principle axis + */ + //Eigen::MatrixXf + void LiDARTag::_estimatePrincipleAxis(ClusterFamily_t &cluster){ + // Eigen::MatrixXf EigenPC(3, cluster.inliers); + // int eigenpc_index = 0; + // for (int i=0; i svd(EigenPC, Eigen::ComputeFullU); + Eigen::MatrixXf ave = Eigen::MatrixXf::Ones(3, cluster.inliers); + ave.row(0) *= cluster.average.x; + ave.row(1) *= cluster.average.y; + ave.row(2) *= cluster.average.z; + + Eigen::MatrixXf centered_data = cluster.merged_data.topRows(3) - ave; + Eigen::JacobiSVD svd(centered_data, Eigen::ComputeFullU); + cluster.principal_axes = svd.matrixU(); + + // Eigen::Matrix4f m1 = MatrixXd::Random(4,4); + // Eigen::Matrix4f m1; + // m1 << 1, 2, 3, 4, + // 5, 6, 7, 8, + // 9, 10,11,12, + // 13, 14,15,16; + // Eigen::MatrixXf m2 = Eigen::MatrixXf::Ones(4,4); + // m2.row(0) *= 1; + // m2.row(1) *= 2; + // m2.row(2) *= 3; + // m2.row(3) *= 4; + // cout << "m1: \n" << m1 << endl; + // cout << "m2: \n" << m2 << endl; + // cout << "m1 - [1;2;3;4]: \n" << m1 -m2<< endl; + // cout<< "m1.row(0) - 1: " << m1.row(0) - 1*Eigen::MatrixXf::Ones(1, 1) << endl; + // cout<< "m1.row(1) - 2: " << m1.row(1) - 2*Eigen::MatrixXf::Ones(1, 2) << endl; + // cout<< "m1.row(2) - 3: " << m1.row(2) - 3*Eigen::MatrixXf::Ones(1, 4) << endl; + // cout<< "m1.row(3) - 4: " << m1.row(3) - 4*Eigen::MatrixXf::Ones(1, 4) << endl; + + // // cout<< "1: " << Eigen::MatrixXf::Ones(1, 4) << endl; + // m1.row(0) -= 1*Eigen::MatrixXf::Ones(1, 4); + // m1.row(1) -= 2*Eigen::MatrixXf::Ones(1, 4); + // m1.row(2) -= 3*Eigen::MatrixXf::Ones(1, 4); + // m1.row(3) -= 4*Eigen::MatrixXf::Ones(1, 4); + // cout << "m1: \n" << m1 << endl; + + // ROS_INFO_STREAM("principal_axes: " << svd.matrixU()); + // ROS_INFO_STREAM("inner_01: " << svd.matrixU().col(0).adjoint()*svd.matrixU().col(1)); + // ROS_INFO_STREAM("inner_02: " << svd.matrixU().col(0).adjoint()*svd.matrixU().col(2)); + // ROS_INFO_STREAM("inner_12: " << svd.matrixU().col(1).adjoint()*svd.matrixU().col(2)); + if (_debug_info) { + ROS_DEBUG_STREAM("==== _estimatePrincipleAxis ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + Eigen::VectorXf sv = svd.singularValues(); + ROS_DEBUG_STREAM("Singular values: " << sv[0] << ", " << sv[1] << ", " << sv[2]); + } + + + // flip through xy plane + // Eigen::Matrix3f m; + // m << 0, 1, 0, + // 0, 0, 1, + // 1, 0, 0; + + // m << 0,1,0, + // 1,0,0, + // 0,0,1; + + // m << 0,0,1, + // 1,0,0, + // 0,1,0; + // m << 0,0,1, + // 0,1,0, + // 1,0,0; + + // m << 1,0,0, + // 0,0,1, + // 0,1,0; + // cout << "Normal Vector1: \n" << normal_vector_robot << endl; + // normal_vector_robot = (m*normal_vector_robot).eval(); + // cout << "Normal Vector2: \n" << normal_vector_robot << endl; + + // Make sure consistency + // Eigen::Vector3f position(cluster.average.x, cluster.average.y, cluster.average.z); + // if(position.transpose()*normal_vector_robot < 0) normal_vector_robot = (-normal_vector_robot).eval(); + //if (normal_vector_robot(0)>=0) normal_vector_robot = (-normal_vector_robot).eval(); + // cout << position << "Normal Vector3: \n" << normal_vector_robot << endl;************ + + // Coordinate transform + // Eigen::Matrix normal_vector_tag; + // normal_vector_tag << normal_vector_robot(2), normal_vector_robot(0), normal_vector_robot(1); + // normal_vector_tag << normal_vector_robot(0), normal_vector_robot(2), normal_vector_robot(1); + + + //return normal_vector_robot;*************** + + // pcl::PointCloud::Ptr Cloud (new pcl::PointCloud); + + // for (int i=0; ipoint.x, + // cluster.payload[i]->point.y, + // cluster.payload[i]->point.z}; + // cout << "point: " << point << endl; + // Cloud->push_back(point); + // } + // pcl::PointCloud::Ptr normals (new pcl::PointCloud); + + // // pcl::IntegralImageNormalEstimation ne; + // // ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT); + // // ne.setMaxDepthChangeFactor(0.02f); + // // ne.setNormalSmoothingSize(10.0f); + // // ne.setInputCloud(Cloud); + // // ne.compute(*normals); + // // cout << "NV: " << *normals << endl; + + // pcl::NormalEstimation NE; + // NE.setInputCloud (Cloud); + // pcl::search::KdTree::Ptr tree (new pcl::search::KdTree ()); + // NE.setSearchMethod (tree); + + // // Output datasets + // pcl::PointCloud::Ptr CloudNormals (new pcl::PointCloud); + // NE.setRadiusSearch (1); + // NE.compute (*CloudNormals); + // cout << "normals: " << *CloudNormals << endl; + // std::cout << "cloud_normals->points.size (): " << CloudNormals->points.size () << std::endl; + // + // return CloudNormals; + } + + /* + * A function of ros spin + * reason: in order to put it into background as well as able to run other tasks + */ + void LiDARTag::_rosSpin(){ + while (ros::ok() && !_stop){ + ros::spinOnce(); + } + } + + /* + * A function to transform from a customized type (LiDARpoints_t) + * of vector of vector (edge_buff) + * into a standard type (PointXYZRI) of pcl vector (out) + */ + void LiDARTag::_buffToPclVector( + const std::vector> &edge_buff, + pcl::PointCloud::Ptr Out){ + for (int ringnumber=0; ringnumber<_beam_num; ++ringnumber){ + if (edge_buff.at(ringnumber).size()!=0){ + for (int i=0; ipush_back(edge_buff[ringnumber][i].point); + } + } + } + } + + /* + * A function to draw a line between two points + */ + void LiDARTag::_assignLine(visualization_msgs::Marker &Marker, visualization_msgs::MarkerArray MarkArray, + const uint32_t Shape, const string ns, + const double r, const double g, const double b, + const PointXYZRI point1, const PointXYZRI point2, const int count){ + Marker.header.frame_id = _pub_frame; + Marker.header.stamp = _current_scan_time; + //Marker.ns = string("Boundary_") + to_string(cluster.cluster_id); + Marker.ns = ns; + Marker.id = count; + Marker.type = Shape; + + Marker.action = visualization_msgs::Marker::ADD; + Marker.pose.orientation.x = 0.0; + Marker.pose.orientation.y = 0.0; + Marker.pose.orientation.z = 0.0; + Marker.pose.orientation.w = 1.0; + + // Set the scale of the marker -- 1x1x1 here means 1m on a side + Marker.scale.x = 1; + + // Set the color -- be sure to set alpha to something non-zero! + Marker.color.r = r; + Marker.color.g = g; + Marker.color.b = b; + Marker.color.a = 1.0; + + geometry_msgs::Point p; + p.x = point1.x; + p.y = point1.y; + p.z = point1.z; + Marker.points.push_back(p); + p.x = point2.x; + p.y = point2.y; + p.z = point2.z; + Marker.points.push_back(p); + MarkArray.markers.push_back(Marker); + } + + /* + * A function to transform an eigen type of vector to pcl point type + */ + void LiDARTag::_eigenVectorToPointXYZRI(const Eigen::Vector4f &Vector, PointXYZRI &point){ + point.x = Vector[0]; + point.y = Vector[1]; + point.z = Vector[2]; + // point.intensity = Vector[3]; // TODO: is this okay? + } + + /* + * A function to transform a pcl point type to an eigen vector + */ + void LiDARTag::_PointXYZRIToEigenVector(const PointXYZRI &point, Eigen::Vector4f &Vector){ + Vector[0] = point.x; + Vector[1] = point.y; + Vector[2] = point.z; + Vector[3] = point.intensity; + } + + /* [not used] [not finished] + * A function to group edges + */ + template + void LiDARTag::_freeVec(Container& c) { + while(!c.empty()) { + if (c.back()!=nullptr) { + delete c.back(); + c.back()=nullptr; + } + c.pop_back(); + } + } + + void LiDARTag::_freePCL(pcl::PointCloud &vec){ + while(!vec.empty()) delete vec.back(), vec.erase(vec.end()); + } + + void LiDARTag::_freeTagLineStruc(TagLines_t &tag_edges){ + LiDARTag::_freeVec(tag_edges.upper_line); + LiDARTag::_freeVec(tag_edges.lower_line); + LiDARTag::_freeVec(tag_edges.left_line); + LiDARTag::_freeVec(tag_edges.right_line); + + LiDARTag::_freeVec(tag_edges.bottom_left); + LiDARTag::_freeVec(tag_edges.bottom_right); + LiDARTag::_freeVec(tag_edges.top_left); + LiDARTag::_freeVec(tag_edges.top_right); + } + + void LiDARTag::_printStatistics( + const std::vector &cluster_buff) { + // XXX: timings are all in milliseconds + auto valid_clusters = _getValidClusters(cluster_buff); + ROS_INFO_STREAM("[Writing CSV] Remaining Clusters: " + << valid_clusters.size()); + + std::ofstream fstats; + std::ofstream ftiming; + std::ofstream fpose; + std::ofstream fclusters; + std::ofstream fdecoding; + std::ofstream fcorners; + + // fstats + if (_iter == 0) { + fstats.open(_outputs_path + "/stats.txt", ios::trunc); + if (!fstats.is_open()) { + cout << "Could not open stats.txt: " << _outputs_path + << "\n Currently at: " << __LINE__ << endl; + exit(0); + } + fstats << "iter, pc size, PoI size, clusters size, " + << "minimum return, maximum return, " + << "plane fitting, plane outliers, " + << "boundary points, ring points, no edges, line fitting, " + << "pose optimization, decoding fail, " + << "remaining" + << endl; + } else { + fstats.open(_outputs_path + "/stats.txt", + std::ofstream::out | std::ofstream::app); + if (!fstats.is_open()) { + cout << "Could not open stats.txt: " << _outputs_path + << "\n Currently at: " << __LINE__ << endl; + exit(0); + } + } + // Summary: + // - Original point cloud size + // - Edge cloud size (analyzing depth discontinuity) + // - cluster size + // - Removal by point check (didnt meet points falling in area check) + // - Removal by boundary point check (sqrt(tag_family)*2) + // - Removal by no_edge_check (not used) + // - Removal by minimum return (decoding pts + boundary_pts) + // - Number of remaining clusters after all removals + + fstats << _iter << ","; + fstats << _result_statistics.point_cloud_size << ","; + fstats << _result_statistics.edge_cloud_size << ","; + fstats << _result_statistics.original_cluster_size << ","; + fstats << _result_statistics.cluster_removal.minimum_return << ","; + fstats << _result_statistics.cluster_removal.maximum_return << ","; + fstats << _result_statistics.cluster_removal.plane_fitting << ","; + fstats << _result_statistics.cluster_removal.plane_outliers << ","; + fstats << _result_statistics.cluster_removal.boundary_point_check << ","; + fstats << _result_statistics.cluster_removal.minimum_ring_points << ","; + fstats << _result_statistics.cluster_removal.no_edge_check << ","; + fstats << _result_statistics.cluster_removal.line_fitting << ","; + fstats << _result_statistics.cluster_removal.pose_optimization << ","; + fstats << _result_statistics.cluster_removal.decoding_failure << ","; + fstats << _result_statistics.remaining_cluster_size << endl; + fstats.close(); + fstats << std::endl; + + // Timing + if (_debug_time) { + if (_iter == 0) { + ftiming.open(_outputs_path + "/timing_all.txt", ios::trunc); + if (!ftiming.is_open()) { + cout << "Could not open timing_all.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + ftiming << "iter, duration, PoI_clustering, " + << "to_pcl, fill_in_time, point_check, plane_fitting, " + << "line_fitting, avage_edge_points, pca, " + << "split_edge, pose_optimization, store_template, " + << "payload_decoding" << endl; + } else { + ftiming.open(_outputs_path + "/timing_all.txt", + std::ofstream::out | std::ofstream::app); + if (!ftiming.is_open()) { + cout << "Could not open timing_all.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + } + ftiming << _iter << ","; + ftiming << _timing.total_duration << ","; + ftiming << _timing.edging_and_clustering_time << ","; + ftiming << _timing.to_pcl_vector_time << ","; + ftiming << _timing.fill_in_time << ","; + ftiming << _timing.point_check_time << ","; + ftiming << _timing.plane_fitting_removal_time << ","; + ftiming << _timing.line_fitting_time << ","; + ftiming << _timing.organize_points_time << ","; + ftiming << _timing.pca_time << ","; + ftiming << _timing.split_edge_time << ","; + ftiming << _timing.pose_optimization_time << ","; + ftiming << _timing.store_template_time << ","; + ftiming << _timing.payload_decoding_time << endl; + ftiming.close(); + } else { + if (_iter == 0) { + ftiming.open(_outputs_path + "/timing_computation_only.txt", ios::trunc); + if (!ftiming.is_open()) { + cout << "Could not open computation_time.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + ftiming << "iter, duration" << endl; + } else { + ftiming.open(_outputs_path + "/timing_computation_only.txt", + std::ofstream::out | std::ofstream::app); + if (!ftiming.is_open()) { + cout << "Could not open computation_time.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + } + ftiming << _iter << ", "; + ftiming << _timing.total_duration << endl; + ftiming.close(); + } + + // decoding + if (_debug_decoding_time) { + if (_iter == 0) { + fdecoding.open(_outputs_path + "/decoding_analysis.txt", ios::trunc); + if (!fdecoding.is_open()) { + cout << "Could not open decoding_analysis.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + fdecoding << "iter, original, matrix, vector, " + << "tbb original, tbb vec, " + << "manual scdl tbb vec, tbb scdl tbb vec, " + << "tbb kd tree" + << endl; + } else { + fdecoding.open(_outputs_path + "/decoding_analysis.txt", + std::ofstream::out | std::ofstream::app); + if (!fdecoding.is_open()) { + cout << "Could not open decoding_analysis.txt: " << _outputs_path + << "\n Currently at " << __FILE__ << " at "<< __LINE__ << endl; + exit(0); + } + } + fdecoding << _iter << ", "; + fdecoding << _time_decoding.original << ", "; + fdecoding << _time_decoding.matrix << ", "; + fdecoding << _time_decoding.vectorization << ", "; + fdecoding << _time_decoding.tbb_original << ", "; + fdecoding << _time_decoding.tbb_vectorization << ", "; + fdecoding << _time_decoding.manual_scheduling_tbb_vectorization << ", "; + fdecoding << _time_decoding.tbb_scheduling_tbb_vectorization << ", "; + fdecoding << _time_decoding.tbb_kd_tree << endl; + fdecoding.close(); + } + + + // pose and clustering + if (_iter == 0) { + for (int i = 0; i < _num_tag_sizes; ++i) { + std::string _tag_file_path = + _outputs_path + "tag_size" + + std::to_string(_tag_size_list[i]) + "pose.txt"; + fpose.open(_tag_file_path, std::ofstream::trunc); + if (!fpose.is_open()) { + cout << "Could not open fpose file: " << _tag_file_path + << "Currently at :" << __LINE__ << endl; + exit(0); + } + // fpose << "iter, id, rot_num, x, y, z, r, p, y"; + fpose << "iter, id, rot_num, x, y, z, r11, r12, r13, "; + fpose << "r21, r22, r23, r31, r32, r33" << endl; + fpose << std::endl; + fpose.close(); + } + + for (int i = 0; i < _num_tag_sizes; ++i) { + std::string _corners_file_path = + _outputs_path + "tag_size" + + std::to_string(_tag_size_list[i]) + "corners.txt"; + fcorners.open(_corners_file_path, std::ofstream::trunc); + if (!fcorners.is_open()) { + cout << "Could not open fcorners file: " << _corners_file_path + << "Currently at :" << __LINE__ << endl; + exit(0); + } + // fpose << "iter, id, rot_num, x, y, z, r, p, y"; + fcorners << "iter, 1x, 1y, 1z, 2x, 2y, 2z, 3x, 3y, 3z, 4x, 4y, 4z" << endl; + fcorners << std::endl; + fcorners.close(); + } + + + fclusters.open(_outputs_path + "/clusters.txt", std::ofstream::trunc); + if (!fclusters.is_open()) { + cout << "Could not open cluster file: " << _outputs_path + << "Currently at :" << __LINE__ << endl; + exit(0); + } + fclusters << "iter, cluster size, cluter points" << endl; + } else { + fclusters.open(_outputs_path + "/clusters.txt", + std::ofstream::out | std::ofstream::app); + if (!fclusters.is_open()) { + cout << "Could not open cluster file: " << _outputs_path + << "Currently at :" << __LINE__ << endl; + exit(0); + } + } + + + if (valid_clusters.size() > 0) { + fclusters << _iter << ","; + fclusters << valid_clusters.size() << ","; + for (const auto cluster_idx : valid_clusters) { + std::string _tag_file_path = + _outputs_path + "tag_size" + + std::to_string(cluster_buff[cluster_idx].tag_size) + + "pose.txt"; + fpose.open(_tag_file_path, + std::ofstream::out | std::ofstream::app); + fpose << _iter << ","; + fpose << cluster_buff[cluster_idx].rkhs_decoding.id << ","; + fpose << cluster_buff[cluster_idx].rkhs_decoding.rotation_angle + << ","; + fpose << cluster_buff[cluster_idx].pose.translation(0) << ", " + << cluster_buff[cluster_idx].pose.translation(1) << ", " + << cluster_buff[cluster_idx].pose.translation(2) << ", "; + + fpose << cluster_buff[cluster_idx].pose.rotation(0, 0) << ", " + << cluster_buff[cluster_idx].pose.rotation(0, 1) << ", " + << cluster_buff[cluster_idx].pose.rotation(0, 2) << ", " + << cluster_buff[cluster_idx].pose.rotation(1, 0) << ", " + << cluster_buff[cluster_idx].pose.rotation(1, 1) << ", " + << cluster_buff[cluster_idx].pose.rotation(1, 2) << ", " + << cluster_buff[cluster_idx].pose.rotation(2, 0) << ", " + << cluster_buff[cluster_idx].pose.rotation(2, 1) << ", " + << cluster_buff[cluster_idx].pose.rotation(2, 2) << ""; + // fpose << cluster_buff[cluster_idx].pose.roll << ","; + // fpose << cluster_buff[cluster_idx].pose.pitch << ","; + // fpose << cluster_buff[cluster_idx].pose.yaw << ","; + fpose << std::endl; + fclusters << cluster_buff[cluster_idx].data.size() << ","; + fpose.close(); + + Eigen::Vector4f corner_lidar1(0, cluster_buff[cluster_idx].tag_size/2, cluster_buff[cluster_idx].tag_size/2, 1); + Eigen::Vector4f corner_lidar2(0, cluster_buff[cluster_idx].tag_size/2, -cluster_buff[cluster_idx].tag_size/2, 1); + Eigen::Vector4f corner_lidar3(0, -cluster_buff[cluster_idx].tag_size/2, -cluster_buff[cluster_idx].tag_size/2, 1); + Eigen::Vector4f corner_lidar4(0, -cluster_buff[cluster_idx].tag_size/2, cluster_buff[cluster_idx].tag_size/2, 1); + Eigen::Vector4f corner_tag1 = cluster_buff[cluster_idx].pose.homogeneous * corner_lidar1; + Eigen::Vector4f corner_tag2 = cluster_buff[cluster_idx].pose.homogeneous * corner_lidar2; + Eigen::Vector4f corner_tag3 = cluster_buff[cluster_idx].pose.homogeneous * corner_lidar3; + Eigen::Vector4f corner_tag4 = cluster_buff[cluster_idx].pose.homogeneous * corner_lidar4; + std::string _corners_file_path = + _outputs_path + "tag_size" + + std::to_string(cluster_buff[cluster_idx].tag_size) + + "corners.txt"; + fcorners.open(_corners_file_path, + std::ofstream::out | std::ofstream::app); + fcorners << _iter << ","; + fcorners << corner_tag1(0) << ","; + fcorners << corner_tag1(1) << ","; + fcorners << corner_tag1(2) << ","; + fcorners << corner_tag2(0) << ","; + fcorners << corner_tag2(1) << ","; + fcorners << corner_tag2(2) << ","; + fcorners << corner_tag3(0) << ","; + fcorners << corner_tag3(1) << ","; + fcorners << corner_tag3(2) << ","; + fcorners << corner_tag4(0) << ","; + fcorners << corner_tag4(1) << ","; + fcorners << corner_tag4(2) << ","; + fcorners << std::endl; + fcorners.close(); + + } + + } + fclusters << std::endl; + fclusters.close(); + + + + + _iter ++; + } + + std::vector + LiDARTag::_getValidClusters( + const std::vector &cluster_buff) { + std::vector valid_clusters {}; + for (int i = 0; i < cluster_buff.size(); ++i) { + if (cluster_buff[i].valid) { + valid_clusters.push_back(i); + } + } + std::sort(valid_clusters.begin(), valid_clusters.end(), [&](int idx1, int idx2) { + return cluster_buff[idx1].data.size() < cluster_buff[idx2].data.size(); + }); + return valid_clusters; + } + + + // void LiDARTag::_saveTemporalCluster(const std::vector &t_cluster, std::vector>>& matData) + // { + // //if first time retrieve the data from cluster to mat file + // if (matData.empty()){ + // int num_cluster = t_cluster.size(); + // for(int i = 0 ; i < num_cluster; ++i){ + // std::vector> target; + // target.push_back(t_cluster[i].data); + // matData.push_back(target); + // } + // } + + // //check if cluster nums stay consistent with previous recognized nums + // if (t_cluster.size() != matData.size()){ + // printf("Num of targets not consistent! \n" ); + // exit(0); + // } + + // //append new pointclouds to matData + // for(int i = 0; i < t_cluster.size(); ++i){ + // matData[i].push_back(t_cluster[i].data); + // } + // } + + // void LiDARTag::_saveMatFiles(std::vector>>& matData){ + + // int num_files = matData.size(); + // for(auto pcs : matData){ + // int depth = pcs.size(); + // //find the max num of points in the temporal series + // vector>::iterator max_itr= max_element(pcs.begin(),pcs.end(),[](pcl::PointCloud &A, pcl::PointCloud &B){ + // return A.size() < B.size(); + // }); + // int length = (*max_itr).size(); + + // //open matfiles + // std::string path = _mat_file_path + "pc" + std::to_string(num_files--); + // MATFile *pmat = matOpen(path.c_str(), "w"); + + // if (pmat == NULL) { + // printf("Error creating file %s\n", path.c_str()); + // printf("(Do you have write permission in this directory?)\n"); + // exit(0); + // } + + // const mwSize dims[]={depth,length,5}; + // mxArray* plhs = mxCreateNumericArray(3, dims, mxDOUBLE_CLASS, mxREAL); + + // double *ptr = mxGetDoubles(plhs); + // //assign pointclouds to mat files + // for(int i = 0; i < depth; ++i){ + // int j = 0; + // for(const auto &p : pcs[i]){ + // ptr[i*length*5+j*5+0] = (double)p.point.x; + // ptr[i*length*5+j*5+1] = (double)p.point.y; + // ptr[i*length*5+j*5+2] = (double)p.point.z; + // ptr[i*length*5+j*5+3] = (double)p.point.intensity; + // ptr[i*length*5+j*5+4] = (double)p.point.ring; + // j++; + // } + // //filling all empty cells as 0 + // for(;j _distance_threshold) + detection.id = 1; + else + detection.id = 3; + } + + detection.size = detection.id == 1? 1.215 : 0.8; + + pcl::PointCloud::Ptr clusterPC(new pcl::PointCloud); + for (int i=0; ipush_back(cluster.data[i].point); + } + // std::cout << "LiDARTag cluster size" << cluster.data.size() << std::endl; + + sensor_msgs::PointCloud2 pcs_waited_to_pub; + pcl::toROSMsg(*clusterPC, pcs_waited_to_pub); + detection.points = pcs_waited_to_pub; + detectionsToPub.detections.push_back(detection); + // if (detectionsToPub.detections.size() > 2) + // ROS_INFO_STREAM("LiDARTag Got wrong tags"); + } +} // namespace BipedLab diff --git a/src/lidartag_cluster.cc b/src/lidartag_cluster.cc new file mode 100644 index 0000000..2b22fbd --- /dev/null +++ b/src/lidartag_cluster.cc @@ -0,0 +1,386 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + +#include // package +#include "lidartag.h" +#include "ultra_puck.h" + +#include + +#define _SQRT2 1.41421356237 + +using namespace std; + +namespace BipedLab { + + /* + * A function to cluster a single point into a new cluster or an existing cluster + */ + void LiDARTag::_clusterClassifier(const LiDARPoints_t &point, vector &cluster_buff){ + // The first time to cluster the point cloud + int ValidCluster = 1; // Marker every cluster is valid and will be checked again later + if (cluster_buff.size()==0){ + int bottom_ring = point.point.ring; + int top_ring = point.point.ring; + PointXYZRI top_most_point = point.point; + top_most_point.z = top_most_point.z + _linkage_threshold; + PointXYZRI bottom_most_point = point.point; + bottom_most_point.z -= _linkage_threshold; + + PointXYZRI front_most_point = point.point; + front_most_point.x += _linkage_threshold; + + PointXYZRI back_most_point = point.point; + back_most_point.x -= _linkage_threshold; + + PointXYZRI right_most_point = point.point; + right_most_point.y -= _linkage_threshold; + PointXYZRI left_most_point = point.point; + left_most_point.y += _linkage_threshold; + //cout << "_linkage_threshold:" << _linkage_threshold << endl; + // + //cout << "\033[1;31m============== \033[0m\n"; + //cout << "First created" << endl; + //cout << "TopMost: " << top_most_point.x << ", " << top_most_point.y << ", " << top_most_point.z << endl; + //cout << "bottom_most_point: " << bottom_most_point.x << ", " << bottom_most_point.y << ", " << bottom_most_point.z << endl; + //cout << "Front: " << front_most_point.x << ", " << front_most_point.y << ", " << front_most_point.z << endl; + //cout << "back: " << back_most_point.x << ", " << back_most_point.y << ", " << back_most_point.z << endl; + //cout << "Right: " << right_most_point.x << ", " << right_most_point.y << ", " << right_most_point.z << endl; + //cout << "Left: " << left_most_point.x << ", " << left_most_point.y << ", " << left_most_point.z << endl; + + ClusterFamily_t current_cluster = + {0, ValidCluster, + top_ring, bottom_ring, top_most_point, bottom_most_point, + front_most_point, back_most_point, + right_most_point, left_most_point, + point.point}; + + MaxMin_t initial_value; // = {(int)1e8, 0, -1}; + initial_value.min = (int) 1e8; + initial_value.average = (int) -1; + initial_value.max = (int) -1; + + current_cluster.max_min_index_of_each_ring.resize(_beam_num, initial_value); + current_cluster.max_min_index_of_each_ring[point.point.ring].max = point.index; + current_cluster.max_min_index_of_each_ring[point.point.ring].min = point.index; + + current_cluster.max_intensity = point.point; + current_cluster.min_intensity = point.point; + + current_cluster.edge_points.push_back(point); + cluster_buff.push_back(current_cluster); + return ; + } + else { + // Take a point to go through all the existing cluster to see if this + // point belongs to any of them + // Once it is found belonging to one of the clusters then return. + // After looping though and couldn't find a belonging group then add it + // to a new cluster + TestCluster_t *new_cluster = new TestCluster_t{0}; + //cout << "\033[1;31m============== \033[0m\n"; + //cout << "cluster_buff size: " << cluster_buff.size() << endl; + for (int i=0; iflag)) { + delete new_cluster; + + return; + } + } + // Add a new cluster + if (new_cluster->flag){ + //cout << "new cluster added" << endl; + int Newcluster_id = cluster_buff.size(); + int top_ring = point.point.ring; + int bottom_ring = point.point.ring; + + PointXYZRI top_most_point = point.point; + top_most_point.z += _linkage_threshold; + PointXYZRI bottom_most_point = point.point; + bottom_most_point.z -= _linkage_threshold; + + PointXYZRI front_most_point = point.point; + front_most_point.x += _linkage_threshold; + PointXYZRI back_most_point = point.point; + back_most_point.x -= _linkage_threshold; + + PointXYZRI right_most_point = point.point; + right_most_point.y -= _linkage_threshold; + PointXYZRI left_most_point = point.point; + left_most_point.y += _linkage_threshold; + + //cout << "TopMost: " << top_most_point.x << ", " << top_most_point.y << ", " << top_most_point.z << endl; + //cout << "bottom_most_point: " << bottom_most_point.x << ", " << bottom_most_point.y << ", " << bottom_most_point.z << endl; + //cout << "Front: " << front_most_point.x << ", " << front_most_point.y << ", " << front_most_point.z << endl; + //cout << "back: " << back_most_point.x << ", " << back_most_point.y << ", " << back_most_point.z << endl; + //cout << "Right: " << right_most_point.x << ", " << right_most_point.y << ", " << right_most_point.z << endl; + //cout << "Left: " << left_most_point.x << ", " << left_most_point.y << ", " << left_most_point.z << endl; + + + // Check every time when new marker added + // visualization_msgs::MarkerArray CheckArray; + // visualization_msgs::Marker CheckMarker; + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check0", + // 1, 0, 0, + // top_most_point, 0, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check1", + // 1, 0, 0, + // bottom_most_point, 1, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check2", + // 1, 0, 0, + // front_most_point, 2, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check3", + // 1, 0, 0, + // back_most_point, 3, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check4", + // 1, 0, 0, + // left_most_point, 4, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::CUBE, + // "Check5", + // 1, 0, 0, + // right_most_point, 5, 0.05); + // CheckArray.markers.push_back(CheckMarker); + + // LiDARTag::_assignMarker(CheckMarker, visualization_msgs::Marker::SPHERE, + // "Check6", + // 0, 1, 0, + // Point, 5, 0.1); + // CheckArray.markers.push_back(CheckMarker); + + // _boundary_marker_pub.publish(CheckArray); + //utils::pressEnterToContinue(); + + + new_cluster->new_cluster = + {Newcluster_id, ValidCluster, + top_ring, bottom_ring, top_most_point, bottom_most_point, + front_most_point, back_most_point, + right_most_point, left_most_point, + point.point}; + + // To fill in points between initial points and end points later + MaxMin_t initial_value; // = {(int)1e8, 0, -1}; + initial_value.min = (int) 1e8; + initial_value.average = (int) 0; + initial_value.max = (int) -1; + + new_cluster->new_cluster.max_min_index_of_each_ring.resize(_beam_num, initial_value); + new_cluster->new_cluster.max_min_index_of_each_ring[point.point.ring].max = point.index; + new_cluster->new_cluster.max_min_index_of_each_ring[point.point.ring].min = point.index; + + new_cluster->new_cluster.max_intensity = point.point; + new_cluster->new_cluster.min_intensity = point.point; + + new_cluster->new_cluster.edge_points.push_back(point); + cluster_buff.push_back(new_cluster->new_cluster); + } + delete new_cluster; + } + } + + + /* + * A function update some information about a cluster if this point belongs to + * this cluster; if not belonging to this cluster then return and create a new + * one + */ + void LiDARTag::_updateCluster(const LiDARPoints_t &point, ClusterFamily_t &old_cluster, TestCluster_t *new_cluster){ + // This point is outside of the current cluster + if (!_isWithinCluster(point, old_cluster)) { + + // cout << "\033[1;31m============== \033[0m\n"; + // cout << "New flag" << endl; + // cout << "point: " << point.point.x << ", " << point.point.y << ", " << point.point.z << endl; + // cout << "TOP.z: " << old_cluster.top_most_point.z << ", " << point.point.z << endl; + // cout << "Front.x: " << old_cluster.front_most_point.x << ", " << point.point.x << endl; + // cout << "Left.y: " << old_cluster.left_most_point.y << ", " << point.point.y << endl; + // cout << "Right.y: " << old_cluster.right_most_point.y << ", " << point.point.y << endl; + // cout << "Bottom.z: " << old_cluster.bottom_most_point.z << ", " << point.point.z << endl; + // cout << "Back.x: " << old_cluster.back_most_point.x << ", " << point.point.x << endl; + // utils::pressEnterToContinue(); + new_cluster->flag = 1; + return ; + } + else{ + new_cluster->flag = 0; + } + + // This point is inside this cluster + if (!new_cluster->flag){ + // update the boundary of the old cluster + if (point.point.ring < old_cluster.bottom_ring) { + old_cluster.bottom_ring = point.point.ring; + } + if (point.point.ring > old_cluster.top_ring) { + old_cluster.top_ring = point.point.ring; + } + if (point.point.x + _linkage_threshold > old_cluster.front_most_point.x) { + old_cluster.front_most_point = point.point; + old_cluster.front_most_point.x += _linkage_threshold; + } + if (point.point.x - _linkage_threshold < old_cluster.back_most_point.x) { + old_cluster.back_most_point = point.point; + old_cluster.back_most_point.x -= _linkage_threshold; + } + + if (point.point.y + _linkage_threshold > old_cluster.left_most_point.y) { + old_cluster.left_most_point = point.point; + old_cluster.left_most_point.y += _linkage_threshold; + } + if (point.point.y - _linkage_threshold< old_cluster.right_most_point.y) { + old_cluster.right_most_point = point.point; + old_cluster.right_most_point.y -= _linkage_threshold; + } + + if (point.point.z + _linkage_threshold > old_cluster.top_most_point.z) { + old_cluster.top_most_point = point.point; + old_cluster.top_most_point.z += _linkage_threshold; + } + if (point.point.z - _linkage_threshold < old_cluster.bottom_most_point.z) { + old_cluster.bottom_most_point = point.point; + old_cluster.bottom_most_point.z -= _linkage_threshold; + } + + // update the average // spend around 5-6 HZ + // old_cluster.average.getVector3fMap() = ((old_cluster.average.getVector3fMap() * old_cluster.data.size() + + // point.point.getVector3fMap()) / (old_cluster.data.size()+1)).eval(); + + // update the max/min index of each ring in this cluster + if (old_cluster.max_min_index_of_each_ring[point.point.ring].max < point.index) + old_cluster.max_min_index_of_each_ring[point.point.ring].max = point.index; + + if (old_cluster.max_min_index_of_each_ring[point.point.ring].min > point.index) + old_cluster.max_min_index_of_each_ring[point.point.ring].min = point.index; + + // update the max/min intensity of this cluster + if (old_cluster.max_intensity.intensity < point.point.intensity) + old_cluster.max_intensity = point.point; + + if (old_cluster.min_intensity.intensity > point.point.intensity) + old_cluster.min_intensity = point.point; + + old_cluster.edge_points.push_back(point); + + // cout << "===============================" << endl; + // cout << "point: " << point.point.x << ", "<< point.point.y << ", " << + // point.point.z << ", " << point.point.ring << endl; + // cout << "max: " << old_cluster.max_min_index_of_each_ring[0].max << endl; + // cout << "min: " << old_cluster.max_min_index_of_each_ring[0].min << endl; + // for (auto &it : old_cluster.max_min_index_of_each_ring){ + // cout << "-------" << endl; + // cout << "ring: " << &it - &old_cluster.max_min_index_of_each_ring[0] << endl; + // cout << "max: " << (it).max << endl; + // cout << "min: " << (it).min << endl; + // cout << "average: " << (it).average << endl; + // } + // exit(0); + } + } + + bool LiDARTag::_isWithinCluster(const LiDARPoints_t &point, ClusterFamily_t &cluster) + { + // auto upper_z_threshold = 0; //_threshold + // auto lower_z_threshold = 0; //_threshold + // const double cluster_cushion = _SQRT2; + + // // Calculate upper z threshold + // auto upper_ring = cluster.top_most_point.ring; + // if (upper_ring + 1 <_beam_num) + // { + // // Calculate the expected z distance between the ring of top_most_point + // // and the next ring e.g. the z distance between ring id 20 and 21 + // auto z2 = abs(point.point.x) * UltraPuckV2::EL_TAN.values[upper_ring+1]; + // auto z1 = abs(point.point.x) * UltraPuckV2::EL_TAN.values[upper_ring]; + + // // auto z2 = abs(point.point.x) * tan(UltraPuckV2::el[upper_ring+1]*M_PI/180); + // // auto z1 = abs(point.point.x) * tan(UltraPuckV2::el[upper_ring]*M_PI/180); + // upper_z_threshold += abs(z2 - z1); + // } + + // // Calculate lower z threshold + // auto lower_ring = cluster.bottom_most_point.ring; + // if (lower_ring - 1 > 0) + // { + // // Calculate the expected z distance between the ring of bottom_most_point + // // and the next ring e.g. the z distance between ring id 5 and 4 + // auto z2 = abs(point.point.x) * UltraPuckV2::EL_TAN.values[lower_ring-1]; + // auto z1 = abs(point.point.x) * UltraPuckV2::EL_TAN.values[lower_ring]; + + // // auto z2 = abs(point.point.x) * tan(UltraPuckV2::el[lower_ring-1]*M_PI/180); + // // auto z1 = abs(point.point.x) * tan(UltraPuckV2::el[lower_ring]*M_PI/180); + // // assert(z2 - z1 <= 0); + // lower_z_threshold += abs(z2 - z1); + // } + //TODO: find the correct z threshold + + // return (point.point.z < cluster.average.z + _payload_size) && + // (point.point.x < cluster.average.x + _payload_size) && + // (cluster.average.x - _payload_size < point.point.x) && + // (point.point.y < cluster.average.y + _payload_size) && + // (cluster.average.y - _payload_size < point.point.y) && + // (cluster.average.z - _payload_size < point.point.z); + + // return (point.point.ring == cluster.bottom_ring || point.point.ring == (cluster.bottom_ring - 1)) && + // (point.point.x < cluster.front_most_point.x + _linkage_threshold) && + // (cluster.back_most_point.x - _linkage_threshold < point.point.x) && + // (point.point.y < cluster.left_most_point.y + _linkage_threshold) && + // (cluster.right_most_point.y - _linkage_threshold < point.point.y); + + + return (point.point.ring == cluster.bottom_ring || + point.point.ring == (cluster.bottom_ring - 1)) && + _isWithinClusterHorizon(point, cluster, _linkage_threshold); + } + + bool LiDARTag::_isWithinClusterHorizon( + const LiDARPoints_t &point, ClusterFamily_t &cluster, double threshold) { + return (point.point.x < cluster.front_most_point.x + threshold) && + (cluster.back_most_point.x - threshold < point.point.x) && + (point.point.y < cluster.left_most_point.y + threshold) && + (cluster.right_most_point.y - _linkage_threshold < point.point.y); + } + +} diff --git a/src/lidartag_decode.cc b/src/lidartag_decode.cc new file mode 100644 index 0000000..867fe47 --- /dev/null +++ b/src/lidartag_decode.cc @@ -0,0 +1,2010 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + +#include // package +#include +#include + + +// #include "KDTreeVectorOfVectorsAdaptor.h" +#include "lidartag.h" +#include "apriltag_utils.h" +#include "utils.h" +#include "tag49h14.h" +#include "tag16h5.h" + +using namespace std; + +namespace BipedLab { +void LiDARTag::_getCodeNaive( + string &Code, + pcl::PointCloud payload){ + int topring = 0; + int bottomring = _beam_num; + PointXYZRI tl= payload[0]->point; + PointXYZRI tr= payload[0]->point; + PointXYZRI br= payload[0]->point; + PointXYZRI bl= payload[0]->point; + + + // Find the size of the payload + for (int i=0; ipoint; + if (point.y>tl.y && point.z>tl.z) tl = point; + if (point.y>bl.y && point.ztr.z) tr = point; + if (point.y payload49(_tag_family, 0); + int d = sqrt(_tag_family); + float IntervalY = abs( (tl.y+bl.y)/2 - (tr.y+br.y)/2 ) /(d+_black_border-1); + float IntervalZ = abs( (tl.z+tr.z)/2 - (bl.z+br.z)/2 ) /(d+_black_border-1); + + + if (_fake_tag){ + tl.y = 0; + tl.z = 0; + IntervalY = 1; + IntervalZ = 1; + payload.clear(); + payload.reserve((_tag_family+4*d*_black_border+4*(std::pow(_black_border, 2)))); + float j = 0; + float k = 0; + LiDARPoints_t point; + for (int i=0; i<(_tag_family+4*d*_black_border+4*(std::pow(_black_border, 2))); ++i){ + if (i%(d+2*_black_border)==0 && i!=0) {k++; j=0;} + LiDARPoints_t *point = new LiDARPoints_t{{0, j, k,0,0}, 0,0,0,0}; + payload.push_back(point); + // cout << "j,k: " << j << ", " << k << endl; + j++; + //cout << "payload[i]" << payload[i]->point.y << ", " << payload[i]->point.z << endl; + // delete point; + } + payload[20]->point.intensity = 100; + payload[26]->point.intensity = 100; + payload[27]->point.intensity = 100; + payload[28]->point.intensity = 100; + payload[34]->point.intensity = 100; + payload[36]->point.intensity = 100; + payload[43]->point.intensity = 100; + payload[45]->point.intensity = 100; + } + + + // Calcutate Average intensity for thresholding + float AveIntensity = 0; + for (int i=0; ipoint.intensity; + } + AveIntensity /= payload.size(); + // cout << "size: " << payload.size() << endl; + // cout << "AveIntensity: " << AveIntensity << endl; + + + // Split into grids + for (int i=0; ipoint); + // cout << "i: " << i << endl; + // cout << "point.y: " << pointPtr->y << endl; + // cout << "point.z: " << pointPtr->z << endl; + float DeltaY = abs(pointPtr->y - tl.y); + float DeltaZ = abs(pointPtr->z - tl.z); + + // if (DeltaY==0 || (DeltaY)) { + // if (pointPtr->intensity < AveIntensity) payload49[0] -= 1; + // else payload49[0] += 1; + // continue; + // } + int Y = floor(DeltaY/IntervalY); + int Z = floor(DeltaZ/IntervalZ); + // cout << "Y: " << Y << endl; + // cout << "Z: " << Z << endl; + + // remove black borders + if (Y>=_black_border && Z>=_black_border && Y<=d+_black_border && Z<=d+_black_border){ + int y = (Y-_black_border)%d; // the yth column (remove the black border) + int z = (Z-_black_border)%d; // the zth row (remove the black border) + + int k = d*z + y; // index in a 1D vector + // cout << "y: " << y << endl; + // cout << "z: " << z << endl; + // cout << "k: " << k << endl; + // cout << "intensity: " << pointPtr->intensity << endl; + if (pointPtr->intensity <= AveIntensity) payload49[k] -= 1; + else payload49[k] += 1; + //cout << "payload[k]: " << payload49[k] << endl; + //cout << "--" << endl; + } + + } + + // Threshold into black and white + for (int i=0; i<_tag_family; ++i){ + if (payload49[i]<0) Code += to_string(0); + else Code += to_string(1); + } + + for (int i=0; i<_tag_family; ++i){ + if (i%d==0){ + cout << "\n"; + cout << " " << Code[i]; + } + else{ + cout << " " << Code[i]; + } + } + + + + Code += "UL"; + //cout << "\ncodeB: " << Code << endl; + //0101111111111111UL + //cout << "Code: " << "0010001100011011UL" << endl; + cout << "\nCode 1: \n" << " 0 0 1 0\n 1 1 1 0\n 1 0 1 0\n 0 1 1 1" << endl; + // exit(-1); + // Code = "0010001100011011UL"; + //Code = "0b0000011111100000011000011000110011100000111111111UL"; + // Code = "11111100000011000011000110011100000111111111UL"; //1 + //Code = "0001100111110000011001100011111000000110001100011UL"; // 2 + //cout << "codeA: " << Code << endl; +} + + +/* Decode using Weighted Gaussian weight + * return 0: normal + * return -1: not enough return + * return -2: fail corner detection + */ +int LiDARTag::_getCodeWeightedGaussian(string &Code, Homogeneous_t &pose, + int &payload_points, + const PointXYZRI &average, + const pcl::PointCloud &payload, + const std::vector &payload_boundary_ptr){ + /* p11 + * . p11. . . . . p41 ^ z + * . . . ave . y __| + * p21 . . . p41 . . . + * . . . . + * . p21. . . . . p31 + * p31 + * px2s are just second largest number corresponding to x position + */ + + // For visualization + visualization_msgs::MarkerArray GridMarkerArray; + visualization_msgs::Marker GridMarker; + + visualization_msgs::Marker LineStrip; + LineStrip.header.frame_id = _pub_frame; + LineStrip.header.stamp = _current_scan_time; + LineStrip.ns = "boundary" ; + LineStrip.action = visualization_msgs::Marker::ADD; + LineStrip.pose.orientation.w= 1.0; + LineStrip.id = 1; + LineStrip.type = visualization_msgs::Marker::LINE_STRIP; + LineStrip.scale.x = 0.002; + LineStrip.color.b = 1.0; + LineStrip.color.a = 1.0; + + + + PointXYZRI p11{0, 0, -1000, 0}; + PointXYZRI p21{0, -1000, 0, 0}; + PointXYZRI p31{0, 0, 1000, 0}; + PointXYZRI p41{0, 1000, 0, 0}; + + PointXYZRI p12{0, 0, -1000, 0}; + PointXYZRI p22{0, -1000, 0, 0}; + PointXYZRI p32{0, 0, 1000, 0}; + PointXYZRI p42{0, 1000, 0, 0}; + + + // Find the largest + for (int i=0; ipoint; + + if (point.z>=p11.z) p11 = point; + if (point.y>=p21.y) p21 = point; + if (point.z<=p31.z) p31 = point; + if (point.y<=p41.y) p41 = point; + + } + if(_grid_viz){ + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("11"), + 0, 0, 0, + p11, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("21"), + 0, 0, 0, + p21, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("31"), + 0, 0, 0, + p31, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("41"), + 0, 0, 0, + p41, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + } + + // Find the second large + for (int i=0; ipoint; + if (point.z=p12.z) p12 = point; + if (point.y=p22.y) p22 = point; + + if (point.z>p31.z && point.z<=p32.z) p32 = point; + if (point.y>p41.y && point.y<=p42.y) p42 = point; + } + + if(_grid_viz){ + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("12"), + 0, 0, 0, + p12, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("22"), + 0, 0, 0, + p22, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("32"), + 0, 0, 0, + p32, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("42"), + 0, 0, 0, + p42, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + } + + PointXYZRI p1 = utils::pointsAddDivide(p11, p12, 2); + PointXYZRI p2 = utils::pointsAddDivide(p21, p22, 2); + PointXYZRI p3 = utils::pointsAddDivide(p31, p32, 2); + PointXYZRI p4 = utils::pointsAddDivide(p41, p42, 2); + + // check condition of the detected corners + // if corners are not between certain angle or distance, + // consider the tag is up right => + // change way of detection + int status = utils::checkCorners(_payload_size, p1, p2, p3, p4); + if (status!=0){ + // the tag is up right + p1 = {0, 0,-1000, 0}; + p2 = {0, 0, 1000, 0}; + p3 = {0, 0, 1000, 0}; + p4 = {0, 0,-1000, 0}; + for (int i=0; ipoint; + + // left boundary + if (point.z>=p1.z && point.y > average.y/2) p1 = point; + if (point.z<=p2.z && point.y > average.y/2) p2 = point; + + // right boundary + if (point.z<=p3.z && point.y < average.y/2) p3 = point; + if (point.z>=p4.z && point.y < average.y/2) p4 = point; + } + } + + if(_grid_viz){ + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("1"), + 1, 1, 1, + p1, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("2"), + 1, 1, 1, + p2, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("3"), + 1, 1, 1, + p3, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Grid_" + string("4"), + 1, 1, 1, + p4, 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + GridMarkerArray.markers.push_back(GridMarker); + } + + + int d = std::sqrt(_tag_family); + Eigen:: MatrixXf Vertices = Eigen::MatrixXf::Zero(3,5); + utils::formGrid(Vertices, 0, 0, 0, _payload_size); + Eigen::Matrix3f R; + // Eigen::MatrixXf VerticesOffset = (Vertices.colwise() - utils::toEigen(average)); + // cout << "vertice: " << Vertices << endl; + // cout << "verticeOffset: " << VerticesOffset << endl; + // cout << "Average: " << utils::toEigen(average) << endl; + utils::minus(p1, average); + utils::minus(p2, average); + utils::minus(p3, average); + utils::minus(p4, average); + + utils::fitGrid(Vertices, R, p1, p2, p3, p4); + Eigen::Vector3f Angle = utils::rotationMatrixToEulerAngles(R); + + if(_grid_viz){ + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Model_" + string("1"), + 0, 1, 0, + utils::toVelodyne(Vertices.col(1)), 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Model_" + string("2"), + 0, 1, 0, + utils::toVelodyne(Vertices.col(2)), 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Model_" + string("3"), + 0, 1, 0, + utils::toVelodyne(Vertices.col(3)), 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::CUBE, + "Model_" + string("4"), + 0, 1, 0, + utils::toVelodyne(Vertices.col(4)), 1, 0.01); + GridMarkerArray.markers.push_back(GridMarker); + + geometry_msgs::Point p; + p.x = Vertices(0, 1); + p.y = Vertices(1, 1); + p.z = Vertices(2, 1); + LineStrip.points.push_back(p); + p.x = Vertices(0, 2); + p.y = Vertices(1, 2); + p.z = Vertices(2, 2); + LineStrip.points.push_back(p); + p.x = Vertices(0, 3); + p.y = Vertices(1, 3); + p.z = Vertices(2, 3); + LineStrip.points.push_back(p); + p.x = Vertices(0, 4); + p.y = Vertices(1, 4); + p.z = Vertices(2, 4); + LineStrip.points.push_back(p); + p.x = Vertices(0, 1); + p.y = Vertices(1, 1); + p.z = Vertices(2, 1); + LineStrip.points.push_back(p); + } + + // Calcutate Average intensity for thresholding + float AveIntensity = 0; + for (int i=0; ipoint.intensity; + + AveIntensity /= payload.size(); + + vector Votes(payload.size()); + vector vR(std::pow((d+2*_black_border), 2)); + vector vG(std::pow((d+2*_black_border), 2)); + vector vB(std::pow((d+2*_black_border), 2)); + + // pick a random color for each cell + if(_grid_viz){ + for (int i=0; ipoint); + utils::getProjection(p1, p4, *pointPtr, t14, v14); + utils::getProjection(p1, p2, *pointPtr, t12, v12); + Votes[i].p = pointPtr; + PointXYZRI p; // for visualization + utils::assignCellIndex(_payload_size, R, p, + average, d + 2*_black_border, Votes[i]); + if(_grid_viz){ + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::SPHERE, + "TransPoints", + vR[Votes[i].cell], vG[Votes[i].cell], vB[Votes[i].cell], + p, i, 0.005); + GridMarkerArray.markers.push_back(GridMarker); + } + + } + vector> Grid(std::pow((d+2*_black_border), 2)); + utils::sortPointsToGrid(Grid, Votes); + int TooLessReturn = 0; + int PayloadPointCount = 0; + for (int i=(d+2*_black_border)*_black_border+_black_border; + i<(d+2*_black_border)*(_black_border+d)-_black_border; ++i){ + + if ((i%(d+2*_black_border)<_black_border) || + (i%(d+2*_black_border)>(d+_black_border-1))) continue; + + if (Grid[i].size() < _min_returns_per_grid) TooLessReturn ++; + if (TooLessReturn > _max_decode_hamming) return -1; + + float WeightedProb = 0; + float WeightSum = 0; + float minIntensity = 10000.; + float maxIntensity = -1.; + double r; + double g; + double b; + + // pick a random color for each cell + if(_grid_viz){ + r = (double) rand() / RAND_MAX; + g = (double) rand() / RAND_MAX; + b = (double) rand() / RAND_MAX; + } + + for (int j=0; jp), j, 0.005); + GridMarkerArray.markers.push_back(GridMarker); + LiDARTag::_assignMarker(GridMarker, visualization_msgs::Marker::SPHERE, + "Center" + to_string(i), + 1, 1, 1, + Grid[i][j]->centroid, j, 0.005); + GridMarkerArray.markers.push_back(GridMarker); + LiDARTag::_assignMarker(GridMarker, + visualization_msgs::Marker::TEXT_VIEW_FACING, + "Prob" + to_string(i), + 1, 1, 1, + *(Grid[i][j]->p), j, 0.003, + to_string((Grid[i][j]->p->intensity))); + GridMarkerArray.markers.push_back(GridMarker); + } + WeightedProb += Grid[i][j]->weight*Grid[i][j]->p->intensity; + WeightSum += Grid[i][j]->weight; + } + WeightedProb /= WeightSum; + PayloadPointCount += Grid[i].size(); + + if (WeightedProb>0.5) Code += to_string(1); + else Code += to_string(0); + } + payload_points = PayloadPointCount; + + Code += "UL"; + + if(_grid_viz){ + _payload_grid_pub.publish(GridMarkerArray); + _payload_grid_line_pub.publish(LineStrip); + } + return 0; +} + + +Eigen::MatrixXf +LiDARTag::_construct3DShapeMarker(RKHSDecoding_t &rkhs_decoding, const double &ell) { + Eigen::VectorXf offset_intensity = + rkhs_decoding.template_points.row(3) - + rkhs_decoding.ave_intensity * Eigen::MatrixXf::Ones(1, rkhs_decoding.num_points); + Eigen::VectorXf pos_vec = Eigen::VectorXf::Zero(rkhs_decoding.num_points); + Eigen::VectorXf neg_vec = Eigen::VectorXf::Zero(rkhs_decoding.num_points); + int pos_indx = 0; + int neg_indx = 0; + for (int i = 0; i < rkhs_decoding.num_points; ++i) { + if (offset_intensity[i] >= 0) { + pos_vec[pos_indx] = offset_intensity[i]; + pos_indx ++; + } else { + neg_vec[neg_indx] = offset_intensity[i]; + neg_indx ++; + } + } + pos_vec.conservativeResize(pos_indx); + neg_vec.conservativeResize(neg_indx); + + // compute median + float pos_median = std::abs(utils::computeMedian(pos_vec)); + float neg_median = std::abs(utils::computeMedian(neg_vec)); + // cout << "pos:" << pos_median << endl; + // cout << "neg:" << neg_median << endl; + + pos_vec /= pos_median; + neg_vec /= neg_median; + + pos_vec *= ell; + neg_vec *= ell; + + Eigen::MatrixXf template_points_3D = rkhs_decoding.template_points; + pos_indx = 0; + neg_indx = 0; + for (int i = 0; i < rkhs_decoding.num_points; ++i) { + if (offset_intensity[i] > 0) { + template_points_3D(0, i) = pos_vec[pos_indx]; + pos_indx ++; + } else { + template_points_3D(0, i) = neg_vec[neg_indx]; + neg_indx ++; + } + } + + return template_points_3D; +} + + +void LiDARTag::singleTask( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + score = 0.0; + const Eigen::VectorXf kernel_x = (x_ary - pc1_j(0)).square(); + const Eigen::VectorXf kernel_y = (y_ary - pc1_j(1)).square(); + const Eigen::VectorXf kernel_z = (z_ary - pc1_j(2)).square(); + const Eigen::VectorXf kernel_l = (i_ary - pc1_j(3)).square(); + Eigen::VectorXf geo_kernel = + geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + / (2 * std::pow(geo_ell, 2))).array().exp(); // 1Xnum1 + Eigen::VectorXf feat_kernel = + 1.0 * (-kernel_l.cwiseSqrt() + / (2 * std::pow(feature_ell, 2))).array().exp(); // 1Xnum1 + + score += geo_kernel.dot(feat_kernel); +} + +void LiDARTag::singleTaskFixedSize( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + score = 0.0; + int num_ary = x_ary.cols(); + Eigen::Matrix kernel_x = (x_ary - pc1_j(0)).square(); + Eigen::Matrix kernel_y = (y_ary - pc1_j(1)).square(); + Eigen::Matrix kernel_z = (z_ary - pc1_j(2)).square(); + Eigen::Matrix kernel_l = (i_ary - pc1_j(3)).square(); + Eigen::VectorXf geo_kernel = + geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + / (2 * std::pow(geo_ell, 2))).array().exp(); // 1Xnum1 + Eigen::VectorXf feat_kernel = + 1.0 * (-kernel_l.cwiseSqrt() + / (2 * std::pow(feature_ell, 2))).array().exp(); // 1Xnum1 + + score += geo_kernel.dot(feat_kernel); +} + +void LiDARTag::multipleTasks( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + // cout << "cols: " << pc1_j.cols() << "," << pc1_j.rows() << endl; + // cout << "x_ary.size: " << x_ary.rows() << "," << x_ary.cols() << endl; + // cout << "y_ary.size: " << y_ary.rows() << "," << y_ary.cols() << endl; + // cout << "z_ary.size: " << z_ary.rows() << "," << z_ary.cols() << endl; + // cout << "i_ary.size: " << i_ary.rows() << "," << i_ary.cols() << endl; + score = 0.0; + float score_i = 0; + + for (int i = 0; i < pc1_j.cols(); ++i){ + singleTask(x_ary, y_ary, z_ary, i_ary, + pc1_j.col(i), geo_sig, feature_ell, geo_ell, score_i); + score += score_i; + // const Eigen::VectorXf kernel_x = (x_ary - pc1_j(0, i)).square(); + // const Eigen::VectorXf kernel_y = (y_ary - pc1_j(1, i)).square(); + // const Eigen::VectorXf kernel_z = (z_ary - pc1_j(2, i)).square(); + // const Eigen::VectorXf kernel_l = (i_ary - pc1_j(3, i)).square(); + // Eigen::VectorXf geo_kernel = + // geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + // / (2 * std::pow(geo_ell, 2))).array().exp(); // 1 x num1 + // Eigen::VectorXf feat_kernel = + // 1.0 * (-kernel_l.cwiseSqrt() + // / (2 * std::pow(feature_ell, 2))).array().exp(); // 1 x num1 + + // float dot_prod = geo_kernel.dot(feat_kernel); + // cout << "dot prod" << dot_prod << endl; + // score += dot_prod; + // score += geo_kernel.dot(feat_kernel); + // score += score; + } +} + + +// The issue is when creating many large dynamic eigen array/vector/matrix in +// c++ 11 threads, it overwrites some existing memeory and further +// causes segfault This does not happen if create large fixed-size eigen +// objects. However, due to the fixed-size, it often needs to be large and +// the results are not correct. +void LiDARTag::test( + const Eigen::ArrayXf &x_ary, + const Eigen::ArrayXf &y_ary, + const Eigen::ArrayXf &z_ary, + const Eigen::ArrayXf &i_ary, + const Eigen::MatrixXf &pc1_j, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + // cout << "cols: " << pc1_j.cols() << "," << pc1_j.rows() << endl; + // cout << "x_ary.size: " << x_ary.rows() << "," << x_ary.cols() << endl; + // cout << "y_ary.size: " << y_ary.rows() << "," << y_ary.cols() << endl; + // cout << "z_ary.size: " << z_ary.rows() << "," << z_ary.cols() << endl; + // cout << "i_ary.size: " << i_ary.rows() << "," << i_ary.cols() << endl; + score = 0.0; + float score_i = 0; + float score_3000 = 0; + + + constexpr int pre_set_size = 3000; + int num_ary = x_ary.cols(); + Eigen::Matrix zeros_out_mat = + Eigen::Matrix::Ones(); + zeros_out_mat.segment(num_ary, pre_set_size - 1).setZero(); + // Eigen::VectorXf kernel_x = Eigen::VectorXf::Zero(num_ary); + // Eigen::VectorXf kernel_y = Eigen::VectorXf::Zero(num_ary); + // Eigen::VectorXf kernel_z = Eigen::VectorXf::Zero(num_ary); + // Eigen::VectorXf kernel_l = Eigen::VectorXf::Zero(num_ary); + + for (int i = 0; i < pc1_j.cols(); ++i){ + // singleTask(x_ary, y_ary, z_ary, i_ary, + // pc1_j.col(i), geo_sig, feature_ell, geo_ell, score_i); + //for (int j = 0; j < 4; ++j) { + // cout << pc1_j(j, i) << endl; + //} + int num_ary = x_ary.cols(); + Eigen::Matrix kernel_x_fixed = (x_ary - pc1_j(0)).square(); + Eigen::Matrix kernel_y_fixed = (y_ary - pc1_j(1)).square(); + Eigen::Matrix kernel_z_fixed = (z_ary - pc1_j(2)).square(); + Eigen::Matrix kernel_l_fixed = (i_ary - pc1_j(3)).square(); + Eigen::Matrix kernel_x = + kernel_x_fixed.cwiseProduct(zeros_out_mat); + Eigen::Matrix kernel_y = + kernel_y_fixed.cwiseProduct(zeros_out_mat); + Eigen::Matrix kernel_z = + kernel_z_fixed.cwiseProduct(zeros_out_mat); + Eigen::Matrix kernel_l = + kernel_l_fixed.cwiseProduct(zeros_out_mat); + + + + if (kernel_x.hasNaN()) { + cout << "k_x nan" << endl; + } + if (kernel_y.hasNaN()) { + cout << "k_y nan" << endl; + } + if (kernel_z.hasNaN()) { + cout << "k_z nan" << endl; + } + if (kernel_l.hasNaN()) { + cout << "k_l nan" << endl; + } + Eigen::Matrix geo_kernel_fixed = + geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + / (2 * std::pow(geo_ell, 2))).array().exp(); // 1Xnum1 + Eigen::Matrix feat_kernel_fixed = + 1.0 * (-kernel_l.cwiseSqrt() + / (2 * std::pow(feature_ell, 2))).array().exp(); // 1Xnum1 + + Eigen::Matrix geo_kernel = + geo_kernel_fixed.cwiseProduct(zeros_out_mat); + Eigen::Matrix feat_kernel = + feat_kernel.cwiseProduct(zeros_out_mat); + score_3000 = geo_kernel.dot(feat_kernel); + //cout << "score_3000: " << score_3000 << endl; + // score += score_3000; + + // Eigen::Matrix kernel_x = (x_ary - pc1_j(0, i)); + // Eigen::Matrix kernel_y = (y_ary - pc1_j(1, i)); + // Eigen::Matrix kernel_z = (z_ary - pc1_j(2, i)); + // Eigen::Matrix kernel_l = (i_ary - pc1_j(3, i)); + // score += score_i; + // Eigen::VectorXf geo_kernel = + // geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + // / (2 * std::pow(geo_ell, 2))).array().exp(); // 1 x num1 + // Eigen::VectorXf feat_kernel = + // 1.0 * (-kernel_l.cwiseSqrt() + // / (2 * std::pow(feature_ell, 2))).array().exp(); // 1 x num1 + + // float dot_prod = geo_kernel.dot(feat_kernel); + // cout << "dot prod" << dot_prod << endl; + // score += dot_prod; + // score += geo_kernel.dot(feat_kernel); + // score += score; + } + // auto tmpx = x_ary.cols(); + // auto tmpy = y_ary.cols(); + // auto tmpz = z_ary.cols(); + // auto tmpi = i_ary.cols(); + // auto tmp1 = geo_sig; + // auto tmp2 = feature_ell; + // auto tmp3 = geo_ell; + // score = 0; + // for (int i = 0; i < pc1.cols(); ++i){ + // auto tmp = pc1.col(i); + // score += 0.5; + // } + // // singleTask(x_ary, y_ary, z_ary, i_ary, + // // , geo_sig, feature_ell, geo_ell, score_i); + // // cout << "test" << endl; +} + + +void LiDARTag::computeFunctionVectorInnerProductThreading( + const Eigen::MatrixXf &pc1, const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + float inner_prod_sum = 0.0f; + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + const Eigen::ArrayXf x_ary = pc2.row(0).array(); + const Eigen::ArrayXf y_ary = pc2.row(1).array(); + const Eigen::ArrayXf z_ary = pc2.row(2).array(); + const Eigen::ArrayXf i_ary = pc2.row(3).array(); + + _thread_vec->reset_counter(); + const int quotient = num_pc1 / _num_threads; + const int remainder = num_pc1 % _num_threads; + Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(_num_threads); + int num_tasks = 0; + int start_task = 0; + int num_tasks_tot = 0; + for (int i = 0; i < _num_threads; ++i) { + start_task = quotient * i; + if (i != _num_threads - 1) { + num_tasks = quotient; + } + else { + num_tasks = num_pc1 - quotient * (_num_threads - 1); + } + // cout << "i: " << i << endl; + // cout << "size1: " << num_pc1 << endl; + // cout << "start_task: " << start_task << endl; + // cout << "num_tasks: " << num_tasks << endl; + // cout << "start_task+num_tasks: " << start_task + num_tasks << endl; + // Eigen::MatrixXf test_mat = pc1.block(0, start_task, 4, num_tasks); + std::vector indices(num_tasks); + std::iota(indices.begin(), indices.end(), start_task); + Eigen::MatrixXf test_mat = pc1(Eigen::all, indices); + // _thread_vec->enqueueTask(std::bind(&LiDARTag::test, this, pc1)); + + _thread_vec->enqueueTask(std::bind(&LiDARTag::multipleTasks, this, x_ary, y_ary, + z_ary, i_ary, test_mat, geo_sig, feature_ell, geo_ell, std::ref(score_vec[i]))); + + + + //_thread_vec->enqueueTask(std::bind(&LiDARTag::multipleTasks, this, + // x_ary, y_ary, z_ary, i_ary, + // test_mat, + // geo_sig, feature_ell, geo_ell, std::ref(score_vec[i]))); + } + _thread_vec->wait_until_finished(_num_threads); + score = score_vec.sum()/num_pc1/num_pc2; + + // XXX: works fine and results are correct + // _thread_vec->reset_counter(); + // Eigen::VectorXf score_vec(num_pc1); + // for (int i = 0; i < num_pc1; ++i) { + // _thread_vec->enqueueTask( + // std::bind( + // &LiDARTag::singleTask, this, + // x_ary, y_ary, z_ary, + // i_ary, pc1.col(i), + // geo_sig, feature_ell, geo_ell, + // std::ref(score_vec[i]))); + // } + // _thread_vec->wait_until_finished(num_pc1); + // score = score_vec.sum()/num_pc1/num_pc2; + + + // XXX: works fine and results are correct + // _thread_vec->reset_counter(); + // Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(num_pc1); + // for (int i = 0; i < num_pc1; ++i) { + // _thread_vec->enqueueTask(std::bind(&LiDARTag::multipleTasks, this, + // x_ary, y_ary, z_ary, i_ary, pc1.block(0, i, 4, 1), + // geo_sig, feature_ell, geo_ell, std::ref(score_vec[i]))); + // } + // _thread_vec->wait_until_finished(num_pc1); + // score = score_vec.sum()/num_pc1/num_pc2; + + + // XXX: Running testing function + // _thread_vec->reset_counter(); + // Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(num_pc1); + // for (int i = 0; i < num_pc1; ++i) { + // _thread_vec->enqueueTask(std::bind(&LiDARTag::test, this)); + // } + // _thread_vec->wait_until_finished(num_pc1); + // score = score_vec.sum()/num_pc1/num_pc2; + + + // XXX: Deosn't work + // _thread_vec->reset_counter(); + // const int quotient = num_pc1 / _num_threads; + // const int remainder = num_pc1 % _num_threads; + // Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(_num_threads); + // int num_tasks = 0; + // int start_task = 0; + // int num_tasks_tot = 0; + // for (int i = 0; i < _num_threads; ++i) { + // start_task = quotient * i; + // if (i != _num_threads - 1) { + // num_tasks = quotient; + // } + // else { + // num_tasks = num_pc1 - quotient * (_num_threads - 1); + // } + // // multipleTasks(x_ary, y_ary, z_ary, i_ary, + // // pc1.block(0, start_task, 4, num_tasks), + // // geo_sig, feature_ell, geo_ell, std::ref(score_vec[i])); + // // _thread_vec->enqueueTask(std::bind(&LiDARTag::test, this)); + // num_tasks_tot += num_tasks; + // // constexpr int tmp = num_tasks; + // Eigen::MatrixXf test_mat = pc1.block(0, start_task, 4, num_tasks); + // + // //Eigen::MatrixXf test_mat = Eigen::MatrixXf::Zero(4, num_tasks); + // // for (int j = 0; j < num_tasks; ++j) { + // // test_mat.col(j) = pc1.block<4, 1>(0, start_task); + // // } + // + // // cout << i << "/" << _num_threads << endl; + // // cout << "test_mat: " << test_mat.rows() << "," << test_mat.cols() << endl; + // // cout << "pc1: " << pc1.rows() << "," << pc1.cols() << endl; + // // cout << "start_task, num tasks: " << start_task << "," << num_tasks << endl; + // _thread_vec->enqueueTask(std::bind(&LiDARTag::multipleTasks, this, + // x_ary, y_ary, z_ary, i_ary, + // // std::cref(pc1.block(0, start_task, 4, num_tasks)), + // test_mat, + // // pc1.block(0, 0, 4, 10), + // geo_sig, feature_ell, geo_ell, std::ref(score_vec[i]))); + // } + // // cout << "wait..." << endl; + // _thread_vec->wait_until_finished(_num_threads); + // // std::cout << "score_vec: " << score_vec << endl; + // score = score_vec.sum()/num_pc1/num_pc2; + // // cout << "num_tasks_tot/total tasks: " << num_tasks_tot << "/" << num_pc1 << endl; + // // cout << "score: " << score << endl; + // // cout << "==============================" << endl; + + + + + + + // XXX: sometimes work, sometimes do not + // _thread_vec->reset_counter(); + // constexpr int points_per_task = 2; + // int num_tasks = std::floor(num_pc1 / points_per_task); + // Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(num_tasks); + // for (int task = 0; task < num_tasks; ++task) { + // int start_task = task * points_per_task; + // _thread_vec->enqueueTask(std::bind(&LiDARTag::multipleTasks, this, + // x_ary, y_ary, z_ary, i_ary, + // pc1.block<4, points_per_task>(0, start_task), + // geo_sig, feature_ell, geo_ell, std::ref(score_vec[task]))); + // } + // _thread_vec->wait_until_finished(num_tasks); + // score = score_vec.sum()/num_pc1/num_pc2; +} + + +void LiDARTag::computeFunctionOriginalInnerProductTBB( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::MatrixXf inner_prod = Eigen::MatrixXf::Zero(num_pc1, num_pc2); + tbb::parallel_for(tbb::blocked_range2d (0, num_pc1, _num_threads, 0, num_pc2, _num_threads), + [&inner_prod, &pc1, &pc2, &feature_ell, &geo_sig, geo_ell] (const tbb::blocked_range2d &r) { + for (auto i = r.rows().begin(); i < r.rows().end(); ++i) { + const float feature1 = pc1(3, i); + const Eigen::VectorXf p1 = pc1.block(0, i, 3, 1); + for (auto j = r.cols().begin(); j < r.cols().end(); ++j) { + const float feature2 = pc2(3, j); + const Eigen::VectorXf p2 = pc2.block(0, j, 3, 1); + const float feature_kernel = std::exp( + -std::norm(feature1 - feature2) / (2 * std::pow(feature_ell, 2))); + const float geometry_kernel = geo_sig * std::exp( + -((p1 - p2).norm()) / (2 * std::pow(geo_ell, 2))); + inner_prod(i, j) = feature_kernel * geometry_kernel; + } + }}); + + score = inner_prod.sum()/num_pc1/num_pc2; +} + +void LiDARTag::computeFunctionVectorInnerProductTBBThreadingManualScheduling( + const Eigen::MatrixXf &pc1, const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + const Eigen::ArrayXf x_ary = pc2.row(0).array(); + const Eigen::ArrayXf y_ary = pc2.row(1).array(); + const Eigen::ArrayXf z_ary = pc2.row(2).array(); + const Eigen::ArrayXf i_ary = pc2.row(3).array(); + + + int num_total_tasks = _num_threads * 1; + const int quotient = num_pc1 / num_total_tasks; + const int remainder = num_pc1 % num_total_tasks; + Eigen::VectorXf score_vec = Eigen::VectorXf::Zero(num_total_tasks); + int num_tasks = 0; + int start_task = 0; + int num_tasks_tot = 0; + //for (int i = 0; i < _num_threads; ++i) { + tbb::parallel_for(int(0), num_total_tasks, [&](int i){ + start_task = quotient * i; + if (i != _num_threads - 1) { + num_tasks = quotient; + } + else { + num_tasks = num_pc1 - quotient * (_num_threads - 1); + } + std::vector indices(num_tasks); + std::iota(indices.begin(), indices.end(), start_task); + Eigen::MatrixXf test_mat = pc1(Eigen::all, indices); + multipleTasks(x_ary, y_ary, z_ary, i_ary, test_mat, + geo_sig, feature_ell, geo_ell, std::ref(score_vec[i])); + }); + + score = score_vec.sum()/num_pc1/num_pc2; +} + +void LiDARTag::computeFunctionVectorInnerProductTBBThreadingNoScheduling( + const Eigen::MatrixXf &pc1, const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + const Eigen::ArrayXf x_ary = pc2.row(0).array(); + const Eigen::ArrayXf y_ary = pc2.row(1).array(); + const Eigen::ArrayXf z_ary = pc2.row(2).array(); + const Eigen::ArrayXf i_ary = pc2.row(3).array(); + + // tbb::atomic score_thread = 0; + Eigen::VectorXf score_vec(num_pc1); + tbb::parallel_for(int(0), num_pc1, [&](int i) { + singleTask(x_ary, y_ary, z_ary, i_ary, pc1.col(i), + geo_sig, feature_ell, geo_ell, score_vec[i]); + //score_thread = score_thread + score_vec[i]; + }, tbb::auto_partitioner()); + + // score = score_thread; + score = score_vec.sum()/num_pc1/num_pc2; +} + +void LiDARTag::computeFunctionVectorInnerProductTBBThreadingTBBScheduling( + const Eigen::MatrixXf &pc1, const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + const Eigen::ArrayXf x_ary = pc2.row(0).array(); + const Eigen::ArrayXf y_ary = pc2.row(1).array(); + const Eigen::ArrayXf z_ary = pc2.row(2).array(); + const Eigen::ArrayXf i_ary = pc2.row(3).array(); + tbb::atomic score_thread = 0; + + Eigen::VectorXf score_vec(num_pc1); + // std::vector score_vec(num_pc1); + // tbb::parallel_for(tbb::blocked_range(0, num_pc1), + // [&](const tbb::blocked_range& r, + // const Eigen::ArrayXf &x_ary, + // const Eigen::ArrayXf &y_ary, + // const Eigen::ArrayXf &z_ary, + // const Eigen::ArrayXf &i_ary, + // const Eigen::MatrixXf &pc1, + // const float &geo_sig, + // const float &feature_ell, + // const float &geo_ell, + // Eigen::VectorXf &score_vec){ + // for (int i = r.begin(); i < r.end(); ++i) { + // singleTask(x_ary, y_ary, z_ary, i_ary, pc1.col(i), + // geo_sig, feature_ell, geo_ell, score_vec[i]); + // } + // } + // ); + + score = score_vec.sum()/num_pc1/num_pc2; +} + + +void LiDARTag::computeFunctionVectorInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + float inner_prod_sum = 0.0f; + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + const Eigen::ArrayXf x_ary = pc2.row(0).array(); + const Eigen::ArrayXf y_ary = pc2.row(1).array(); + const Eigen::ArrayXf z_ary = pc2.row(2).array(); + const Eigen::ArrayXf i_ary = pc2.row(3).array(); + Eigen::VectorXf score_vec((int)num_pc1); + for (int j = 0; j < num_pc1; ++j) { + const Eigen::VectorXf kernel_x = (x_ary - pc1(0, j)).square(); + const Eigen::VectorXf kernel_y = (y_ary - pc1(1, j)).square(); + const Eigen::VectorXf kernel_z = (z_ary - pc1(2, j)).square(); + const Eigen::VectorXf kernel_l = (i_ary - pc1(3, j)).square(); + Eigen::VectorXf geo_kernel = + geo_sig * (-(kernel_x + kernel_y + kernel_z).cwiseSqrt() + / (2 * std::pow(geo_ell, 2))).array().exp(); // 1Xnum1 + Eigen::VectorXf feat_kernel = + 1.0 * (-kernel_l.cwiseSqrt() + / (2 * std::pow(feature_ell, 2))).array().exp(); // 1Xnum1 + + inner_prod_sum += geo_kernel.dot(feat_kernel); + } + + score = inner_prod_sum / num_pc1 / num_pc2; +} + + +void LiDARTag::computeFunctionMatrixInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::MatrixXf ones = Eigen::MatrixXf::Ones(1, num_pc2); + Eigen::Vector4f geo_dummy; + Eigen::Vector4f feat_dummy; + geo_dummy << 1,1,1,0; + feat_dummy << 0,0,0,1; + Eigen::MatrixXf inner_prod = Eigen::MatrixXf::Zero(num_pc1, num_pc2); + for (int j = 0; j < num_pc1; ++j) { + Eigen::MatrixXf repmat = pc1.col(j) * ones; + Eigen::MatrixXf kernel = (pc2 - repmat).array().square().matrix(); // 4xnum1 + Eigen::MatrixXf geo_kernel = + geo_sig * (-(geo_dummy.transpose() * kernel).array().sqrt() / + (2 * std::pow(geo_ell, 2))).array().exp(); // 1Xnum1 + Eigen::MatrixXf feat_kernel = + 1.0 * (-(feat_dummy.transpose() * kernel).array().sqrt() / + (2 * std::pow(feature_ell, 2))).array().exp(); // 1Xnum1 + inner_prod.row(j) = (geo_kernel.array() * feat_kernel.array()).matrix(); + } + + score = inner_prod.sum()/num_pc1/num_pc2; +} + + +void LiDARTag::computeFunctionOriginalInnerProduct( + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + // Original double sum + // float score_tmp = 0; + Eigen::MatrixXf inner_prod = Eigen::MatrixXf::Zero(num_pc1, num_pc2); + for (int i = 0; i < num_pc1; ++i) { + float feature1 = pc1(3, i); + Eigen::VectorXf p1 = pc1.block(0, i, 3, 1); + for (int j = 0; j < num_pc2; ++j) { + float feature2 = pc2(3, j); + Eigen::VectorXf p2 = pc2.block(0, j, 3, 1); + float feature_kernel = std::exp( + -std::norm(feature1 - feature2) / (2 * std::pow(feature_ell, 2))); + float geometry_kernel = geo_sig * std::exp( + -((p1 - p2).norm()) / (2 * std::pow(geo_ell, 2))); + // score_tmp += feature_kernel * geometry_kernel; + inner_prod(i, j) = feature_kernel * geometry_kernel; + } + } + score = inner_prod.sum()/num_pc1/num_pc2; + // score = score_tmp; +} + +void LiDARTag::computeFunctionOriginalInnerProductKDTree( + const Eigen::MatrixXf &pc1, + const int &num_pc1, + const Eigen::MatrixXf &pc2, + const int &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + Eigen::MatrixXf pc2_points = pc2.topRows(3); + Eigen::MatrixXf pc2_feat = pc2.bottomRows(1); + + constexpr float sp_thres = 1e-3; + const float search_radius = geo_ell / 2; + // constexpr float sp_thres = 1e-3; + // const float search_radius = geo_ell; + //std::abs(2.0 * geo_ell * geo_ell * std::log(sp_thres / geo_sig)); + // cout << "dis_thre: " << search_radius << endl; + + kd_tree_t mat_index(3 /*dim*/, std::cref(pc2_points), 10 /* max leaf */ ); + mat_index.index->buildIndex(); + tbb::atomic score_thread = 0; + //float score_tmp = 0; + //score = 0; + tbb::concurrent_vector score_vec; + + + tbb::parallel_for(int(0), num_pc1, [&](int i){ + // for(int i = 0; i < num_pc1; ++i){ + const float search_radius_tmp = search_radius; + std::vector> ret_matches; + nanoflann::SearchParams params; + Eigen::Vector3f query = pc2.block<3, 1>(0, i); + vector query_vec(query.data(), query.data() + query.size()); + const size_t n_matches = mat_index.index-> + radiusSearch(&query_vec[0], search_radius_tmp, ret_matches, params); + // cout << "num_matches/total: " << n_matches << " / " << num_pc2 << endl; + float feature1 = pc1(3, i); + for(size_t j = 0; j < n_matches; ++j){ + int idx = ret_matches[j].first; + float dis_squared = ret_matches[j].second; + float feature2 = pc2(3, idx); + float feature_kernel = std::exp( + -std::norm(feature1 - feature2) / (2 * std::pow(feature_ell, 2))); + float geometry_kernel = geo_sig * std::exp( + -(std::sqrt(dis_squared)) / (2 * std::pow(geo_ell, 2))); + // tbb::atomic inner_prod = feature_kernel * geometry_kernel; + float inner_prod = feature_kernel * geometry_kernel; + // cout << "inner_prod: " << inner_prod << endl; + if (inner_prod > sp_thres) + // score_tmp += inner_prod; + // score += inner_prod; + // score_vec.push_back(inner_prod); + score_thread = score_thread + inner_prod; + } + // } + }); + //return score_tmp; + //score = score_tmp; + score = score_thread/num_pc1/num_pc2; + + // for (int i = 0; i < score_vec.size(); ++i) { + // score += score_vec[i]; + // } +} +void LiDARTag::computeFunctionInnerProductModes( + const int mode, + const Eigen::MatrixXf &pc1, + const float &num_pc1, + const Eigen::MatrixXf &pc2, + const float &num_pc2, + const float &geo_sig, + const float &feature_ell, + const float &geo_ell, + float &score){ + // std::clock_t c_start = std::clock(); + switch (mode) { + case 0: + // single thread: original double sum + computeFunctionOriginalInnerProduct( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "Original: "); + break; + case 1: + // single thread: convert to matrices + // c_start = std::clock(); + computeFunctionMatrixInnerProduct( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "Matrix: "); + break; + + case 2: + // single thread: convert matrices to vectors + // c_start = std::clock(); + computeFunctionVectorInnerProduct( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "Vectorization: "); + break; + case 3: + // C++11 thread (works for each point for a thread + // but not for blobs of points for a thread, reason are given above) + // computeFunctionVectorInnerProductThreading( + // pc1, num_pc1, pc2, num_pc2, + // geo_sig, feature_ell, geo_ell, score); + break; + case 4: + // c_start = std::clock(); + computeFunctionOriginalInnerProductTBB( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "TBB Original: "); + break; + case 5: + // c_start = std::clock(); + computeFunctionVectorInnerProductTBBThreadingNoScheduling( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + //utils::printSpendHz(std::clock(), c_start, "No Scheduling TBB Vectorization: "); + break; + case 6: + // c_start = std::clock(); + // computeFunctionVectorInnerProductTBBThreadingManualScheduling( + // pc1, num_pc1, pc2, num_pc2, + // geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "Manual Scheduling TBB Vectorization: "); + break; + case 7: + // c_start = std::clock(); + computeFunctionVectorInnerProductTBBThreadingTBBScheduling( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "TBB Scheduling TBB Vectorization: "); + break; + case 8: + // c_start = std::clock(); + computeFunctionOriginalInnerProductKDTree( + pc1, num_pc1, pc2, num_pc2, + geo_sig, feature_ell, geo_ell, score); + // utils::printSpendHz(std::clock(), c_start, "TBB KDtree: "); + // std::cout << "===================================" << endl; + break; + } +} + + +float LiDARTag::computeFunctionInnerProduct( + const Eigen::MatrixXf &pc1, + const Eigen::MatrixXf &pc2, + const float &geo_ell){ + float feature_ell = 10; + float geo_sig = 1e5; + int num_pc1 = pc1.cols(); + int num_pc2 = pc2.cols(); + float score = 0; + std::chrono::duration duration; + if (num_pc1(num_codes * 4); + float area = tag_size * tag_size; + float id_score = -1; + // Eigen::initParallel(); + // std::clock_t c_start = std::clock(); + float cur_score = 0; + for (int i = 0; i < num_codes ; ++i) { + cur_score = computeFunctionInnerProduct( + rkhs_decoding.template_points_3d, + _function_dic[size_num][i], + rkhs_decoding.ell) / area; + // rkhs_decoding.score[i] = computeFunctionInnerProduct( + // rkhs_decoding.template_points_3d, + // _function_dic[size_num][i], + // rkhs_decoding.ell); + // rkhs_decoding.score[i] = computeFunctionInnerProductKDTree( + // rkhs_decoding.template_points_3d, + // _function_dic[size_num][i], + // rkhs_decoding.ell); + if (cur_score > id_score) { + rkhs_decoding.id = i / 4; + rkhs_decoding.rotation_angle = i % 4; + // rkhs_decoding.id_score = rkhs_decoding.score[i]; + rkhs_decoding.id_score = cur_score; + id_score = rkhs_decoding.id_score; + rkhs_decoding.associated_pattern_3d = &_function_dic[size_num][i]; + } + } + // utils::printSpendHz(std::clock(), c_start, "A cluster decoding: "); + + + // if (rkhs_decoding.template_points_3d.cols() > 1e3) { + // cout << "============" << endl; + // cout << "num_points: " << rkhs_decoding.template_points_3d.cols() << endl;; + // cout << "id:" << rkhs_decoding.id << endl; + // // cout << "id_score:" << rkhs_decoding.id_score << endl; + // cout << "id_score:" << id_score << endl; + // cout << "rotation:" << rkhs_decoding.rotation_angle << endl; + // cout << "File:" << _rkhs_function_name_list[size_num][rkhs_decoding.id] << endl; + // } + + + // utils::printVector(utils::convertEigenToSTDVector(rkhs_decoding.score)); + if (id_score < 12) { + status = 0; + if (_debug_info) { + ROS_WARN_STREAM("==== _getCodeRKHS ===="); + ROS_WARN_STREAM("Size number: " << size_num); + ROS_WARN_STREAM("Score is too small: " << id_score); + ROS_WARN_STREAM("Status: " << status); + ROS_WARN_STREAM("========================"); + } + } else { + status = 1; + if (_debug_info) { + ROS_DEBUG_STREAM("==== _getCodeRKHS ===="); + ROS_DEBUG_STREAM("Size number: " << size_num); + ROS_DEBUG_STREAM("num_points: " << + rkhs_decoding.template_points_3d.cols()); + ROS_DEBUG_STREAM("id: " << rkhs_decoding.id); + ROS_DEBUG_STREAM("id_score: " << rkhs_decoding.id_score); + ROS_DEBUG_STREAM("rotation: " << rkhs_decoding.rotation_angle); + ROS_DEBUG_STREAM("file: " << + _rkhs_function_name_list[size_num][rkhs_decoding.id]); + ROS_DEBUG_STREAM("Status: " << status); + ROS_DEBUG_STREAM("========================"); + } + } + + return status; +} + + +/* [Payload decoding] + * A function to decode payload with different means + * 0: Naive decoding + * 1: Weighted Gaussian + * 2: RKHS + * 3: Deep learning + * 4: ?! + */ +bool LiDARTag::_decodePayload(ClusterFamily_t &Cluster){ + string Code(""); + bool valid_tag = true; + string Msg; + if (_decode_method==0){ // Naive decoder + LiDARTag::_getCodeNaive(Code, Cluster.payload); + } + else if (_decode_method==1) { // Weighted Gaussian + int status = LiDARTag::_getCodeWeightedGaussian( + Code, Cluster.pose_tag_to_lidar, + Cluster.payload_without_boundary, // size of actual payload + Cluster.average, + Cluster.payload, + Cluster.payload_boundary_ptr); + if (status==-1) { + valid_tag = false; + _result_statistics.cluster_removal.decoder_not_return ++; + Cluster.valid = 0; + Msg = "Not enough return"; + } + else if (status==-2) { + valid_tag = false; + _result_statistics.cluster_removal.decoder_fail_corner ++; + Cluster.valid = 0; + Msg = "Fail corner detection"; + } + } + else if (_decode_method==2) { // RKHS + int status = + LiDARTag::_getCodeRKHS(Cluster.rkhs_decoding, Cluster.tag_size); + if (status == 1) { + Cluster.cluster_id = Cluster.rkhs_decoding.id; + } else { + valid_tag = false; + Cluster.valid = 0; + _result_statistics.cluster_removal.decoding_failure ++; + } + } + + if (_decode_method == 0 || _decode_method == 1) { + if (valid_tag) { + uint64_t Rcode = stoull(Code, nullptr, 2); + BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &Cluster.entry); + Cluster.cluster_id = Cluster.entry.id; + ROS_INFO_STREAM("id: " << Cluster.entry.id); + ROS_DEBUG_STREAM("hamming: " << Cluster.entry.hamming); + ROS_DEBUG_STREAM("rotation: " << Cluster.entry.rotation); + } else { + // too big, return as an invalid tag + Code = "1111111111111111UL"; + ROS_DEBUG_STREAM("\nCODE: " << Code); + uint64_t Rcode = stoull(Code, nullptr, 2); + BipedAprilLab::QuickDecodeCodeword(tf, Rcode, &Cluster.entry); + Cluster.cluster_id = 8888; + ROS_DEBUG_STREAM("id: " << Cluster.cluster_id); + ROS_DEBUG_STREAM("hamming: " << Cluster.entry.hamming); + ROS_DEBUG_STREAM("rotation: " << Cluster.entry.rotation); + } + } + + return valid_tag; +} + +/* [Function Decoder] + * A function to load continuous functions from a pre-computed point cloud + */ +void LiDARTag::_initFunctionDecoder(){ + // prepare to rotate functions + Eigen::Vector3f trans_v = Eigen::Vector3f::Zero(3); + Eigen::Vector3f rot_v1; + rot_v1 << 90, 0, 0; + Eigen::Matrix4f H1 = utils::computeTransformation(rot_v1, trans_v); + // cout << "H1: \n" << H1 << endl; + + Eigen::Vector3f rot_v2; + rot_v2 << 180, 0, 0; + Eigen::Matrix4f H2 = utils::computeTransformation(rot_v2, trans_v); + // cout << "H2: \n" << H2 << endl; + + Eigen::Vector3f rot_v3; + rot_v3 << 270, 0, 0; + Eigen::Matrix4f H3 = utils::computeTransformation(rot_v3, trans_v); + // cout << "H3: \n" << H3 << endl; + _function_dic.resize(_num_tag_sizes); + _rkhs_function_name_list.resize(_num_tag_sizes); + std::vector test; + + for (int tag_size = 0; tag_size < _num_tag_sizes; ++tag_size) { + // cout << "path:" << _library_path + std::to_string(tag_size) + "/" + // << endl; + std::string cur_path = _library_path + std::to_string(tag_size) + "/"; + utils::readDirectory(cur_path, _rkhs_function_name_list[tag_size]); + // utils::printVector(_rkhs_function_name_list[tag_size]); + // utils::readDirectory( + // _library_path + std::to_string(tag_size) + "/", test); + // utils::printVector(test); + // consider four rotations + int num_codes = std::min( + (int) _rkhs_function_name_list[tag_size].size(), + _num_codes); + std::vector function_dic(num_codes * 4); + // std::vector function_dic_xyz(num_codes * 4); + // std::vector function_dic_feat(num_codes * 4); + + for (int i = 0, func_ind = 0; i < num_codes * 4; i += 4, ++func_ind) { + // cout << "(i, ind) = (" << i << ", " << func_ind << ")" << endl; + function_dic[i] = utils::loadCSV( + cur_path + _rkhs_function_name_list[tag_size][func_ind]); + // rotate 90 + function_dic[i+1] = + H1 * utils::convertXYZIToHomogeneous(function_dic[i]); + + // rotate 180 + function_dic[i+2] = + H2 * utils::convertXYZIToHomogeneous(function_dic[i]); + + // rotate 270 + function_dic[i+3] = + H3 * utils::convertXYZIToHomogeneous(function_dic[i]); + + + // split points and features for kdtree + // _function_dic_xyz[i] = function_dic[i].topRows + + + + + cout << "function loaded--" + << cur_path + _rkhs_function_name_list[tag_size][func_ind] + << endl; + + // if (i == 0) { + // cout << "tag0: \n" << function_dic[i] << endl; + // cout << "tag_h: \n" << utils::convertXYZIToHomogeneous(function_dic[i]) << endl; + // cout << "H1 * tag_h: \n" << H1 * utils::convertXYZIToHomogeneous(function_dic[i]) << endl; + // } + } + _function_dic[tag_size] = function_dic; + cout << "size: " << _function_dic[tag_size].size() << endl; + } + // _function_dic.resize(_num_codes); // consider four rotations + // for (int i = 0, func_ind = 0; i < _num_codes ; ++i) { + // // cout << "(i, ind) = (" << i << ", " << func_ind << ")" << endl; + // _function_dic[i] = utils::loadCSV( + // _library_path + _rkhs_function_name_list[i]); + // cout << "function loaded--" + // << _library_path + _rkhs_function_name_list[i] << endl; + // // if (i == 0) { + // // cout << "tag0: \n" << _function_dic[i] << endl; + // // cout << "tag_h: \n" << utils::convertXYZIToHomogeneous(_function_dic[i]) << endl; + // // cout << "H1 * tag_h: \n" << H1 * utils::convertXYZIToHomogeneous(_function_dic[i]) << endl; + // // } + // } +} + + + +/* [Decoder] + * Create hash table of chosen tag family + */ +void LiDARTag::_initDecoder(){ + string famname = "tag" + to_string(_tag_family) + "h" + to_string(_tag_hamming_distance); + if (famname == "tag49h14") tf = tag49h14_create(); + else if (famname == "tag16h5") tf = tag16h5_create(); + else { + cout << "[ERROR]" << endl; + cout << "Unrecognized tag family name: "<< famname << ". Use e.g. \"tag16h5\". " << endl; + cout << "This is line " << __LINE__ << " of file "<< __FILE__ << + " (function " << __func__ << ")"<< endl; + exit(0); + } + tf->black_border = _black_border; + cout << "Preparing for tags: " << famname << endl; + if (_decode_method == 0 || _decode_method == 1){ + BipedAprilLab::QuickDecodeInit(tf, _max_decode_hamming); + } + else if (_decode_method == 2){ + LiDARTag::_initFunctionDecoder(); + } +} + +/* + * + */ +void LiDARTag::_testInitDecoder(){ + uint64_t rcode = 0x0001f019cf1cc653UL; + QuickDecodeEntry_t entry; + BipedAprilLab::QuickDecodeCodeword(tf, rcode, &entry); + cout << "code: " << entry.rcode << endl; + cout << "id: " << entry.id << endl; + cout << "hamming: " << entry.hamming << endl; + cout << "rotation: " << entry.rotation << endl; + exit(0); +} +} // namespace BipedLab diff --git a/src/lidartag_pose.cc b/src/lidartag_pose.cc new file mode 100644 index 0000000..6ba8450 --- /dev/null +++ b/src/lidartag_pose.cc @@ -0,0 +1,1418 @@ +#include "lidartag.h" +#include +#include "utils.h" + + +#include + +using namespace std; + +namespace BipedLab { + double checkCost(double point, double cons1, double cons2){ + if (point >= cons1 && point <= cons2) + return 0; + else{ + return std::min(std::abs(point-cons2),std::abs(point-cons1)); + } + } + Eigen::VectorXd d_px_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13) { + double t2 = (rpy12*M_PI)/1.8e+2; + double t3 = (rpy13*M_PI)/1.8e+2; + double t4 = std::cos(t2); + double t5 = std::cos(t3); + double t6 = std::sin(t2); + double t7 = std::sin(t3); + // double test = 0; + Eigen::VectorXd d_px(6); + // d_px << 0.0,0.0,0.0,0.0,0.0,0.0; + d_px << 1.0, 0.0, 0.0, 0.0, + (z11*t4*M_PI)/1.8e+2-(x11*t5*t6*M_PI)/1.8e+2+(y11*t6*t7*M_PI)/1.8e+2, + t4*M_PI*(x11*t7+y11*t5)*(-1.0/1.8e+2); return d_px; + } + + Eigen::VectorXd d_py_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13) { + double t2 = (rpy11*M_PI)/1.8e+2; + double t3 = (rpy12*M_PI)/1.8e+2; + double t4 = (rpy13*M_PI)/1.8e+2; + double t5 = std::cos(t2); + double t6 = std::cos(t3); + double t7 = std::cos(t4); + double t8 = std::sin(t2); + double t9 = std::sin(t3); + double t10 = std::sin(t4); + // double test = 0; + Eigen::VectorXd d_py(6); + // d_py << 0.0,0.0,0.0,0.0,0.0,0.0; + d_py << 0.0, 1.0, 0.0, -x11*((t8*t10*M_PI)/1.8e+2-(t5*t7*t9*M_PI)/1.8e+2)-y11*((t7*t8*M_PI)/1.8e+2+(t5*t9*t10*M_PI)/1.8e+2)-(z11*t5*t6*M_PI)/1.8e+2,(t8*M_PI*(z11*t9+x11*t6*t7-y11*t6*t10))/1.8e+2,x11*((t5*t7*M_PI)/1.8e+2-(t8*t9*t10*M_PI)/1.8e+2)-y11*((t5*t10*M_PI)/1.8e+2+(t7*t8*t9*M_PI)/1.8e+2); + return d_py; + } + + Eigen::VectorXd d_pz_euler(double x11, double y11, double z11, double rpy11, double rpy12, double rpy13) { + double t2 = (rpy11*M_PI)/1.8e+2; + double t3 = (rpy12*M_PI)/1.8e+2; + double t4 = (rpy13*M_PI)/1.8e+2; + double t5 = std::cos(t2); + double t6 = std::cos(t3); + double t7 = std::cos(t4); + double t8 = std::sin(t2); + double t9 = std::sin(t3); + double t10 = std::sin(t4); + // double test = 0; + Eigen::VectorXd d_pz(6); + // d_pz << 0.0,0.0,0.0,0.0,0.0,0.0; + d_pz << 0.0, 0.0, 1.0, x11*((t5*t10*M_PI)/1.8e+2+(t7*t8*t9*M_PI)/1.8e+2)+y11*((t5*t7*M_PI)/1.8e+2-(t8*t9*t10*M_PI)/1.8e+2)-(z11*t6*t8*M_PI)/1.8e+2, t5*M_PI*(z11*t9+x11*t6*t7-y11*t6*t10)*(-1.0/1.8e+2), x11*((t7*t8*M_PI)/1.8e+2+(t5*t9*t10*M_PI)/1.8e+2)-y11*((t8*t10*M_PI)/1.8e+2-(t5*t7*t9*M_PI)/1.8e+2); + return d_pz; + } + + // double costfunc(const std::vector &x, std::vector &grad, void *func_data) { + // // x[0-2] transaltion , x[3-5] euler + // pcl::PointCloud* d = reinterpret_cast*>(func_data); + // const double box_width = 0.02; //0.02 + // const double tag_size = (*d)[d->size()-1].tag_size; + // double total_cost = 0; + // double costx =0 , costy =0, costz= 0; + + // Eigen::Quaternion q = Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) + // * Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) + // * Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + + // Eigen::Matrix3f rotation = q.matrix(); + + // Eigen::Vector3f translation(x[0], x[1], x[2]); + + // Eigen::VectorXf grad_eig = Eigen::VectorXf::Zero(6); + // // if (_debug_info) { + // // ROS_INFO_STREAM("Optimizing pose.... "); + // // } + // for(int i =0; i< d->size()-1; ++i){ + // Eigen::Vector3f p((*d)[i].point.x, (*d)[i].point.y, (*d)[i].point.z); + // Eigen::Vector3f q = rotation * p + translation; + // if (!grad.empty()) { + // // Eigen::VectorXf d_px = d_px_euler(q[0],q[1],q[2],x[3],x[4],x[5]); + // // Eigen::VectorXf d_py = d_py_euler(q[0],q[1],q[2],x[3],x[4],x[5]); + // // Eigen::VectorXf d_pz = d_pz_euler(q[0],q[1],q[2],x[3],x[4],x[5]); + // Eigen::VectorXf d_px(6); + // d_px= d_px_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + // Eigen::VectorXf d_py(6); + // d_py= d_py_euler(q[0],q[1],q[2],x[3],x[4],x[5]); + // Eigen::VectorXf d_pz(6); + // d_pz= d_pz_euler(q[0],q[1],q[2],x[3],x[4],x[5]); + // if (q[0] > box_width) { + // grad_eig = (grad_eig + d_px).eval(); + // } else if (q[0] < -box_width) { + // grad_eig = (grad_eig - d_px).eval(); + // } + // if (q[1] > (tag_size)/2) { + // grad_eig = (grad_eig + d_py).eval(); + // } else if (q[1] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_py).eval(); + // } + // if (q[2] > (tag_size)/2) { + // grad_eig = (grad_eig + d_pz).eval(); + // } else if (q[2] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_pz).eval(); + // } + // } + // costx += checkCost(q[0], -box_width, box_width ); + // costy += checkCost(q[1], -(tag_size)/2, (tag_size)/2); + // costz += checkCost(q[2], -(tag_size)/2, (tag_size)/2); + // } + // // std::cout << "gradients : " << grad_eig[0] << " "< &x, + std::vector &grad, + void *func_data) { + // ROS_INFO_STREAM("Inside ComputeCost"); + // x[0-2] transaltion , x[3-5] euler + Eigen::MatrixXf* d = reinterpret_cast(func_data); + int num_points = d->cols() - 1; // last column is passed as boundary + + // for (int i = 0; i < num_points; ++i) { + // Eigen::Vector3f p((*d)(0, i), (*d)(1, i), (*d)(2, i)); + // if (isnan(p(0)) || isnan(p(1)) || isnan(p(2))) { + // std::cout << "nan idx1 : " << i << std::endl; + // } + // } + const double box_width = (*d)(0, num_points); + const double tag_size = (*d)(0, num_points) * 2; + Eigen::Vector3d q(x[3], x[4], x[5]); + Eigen::Matrix4f H = Eigen::Matrix4f::Identity(4, 4); + H.topLeftCorner(3, 3) = utils::Exp_SO3(q); + H.topRightCorner(3, 1) << x[0], x[1], x[2]; + + + // Eigen::MatrixXf transfomed_points_mat = + // (H * (*d).topLeftCorner(4, num_points)); // 4 x n + + // Eigen::MatrixXf transfomed_cost_ary = + // (transfomed_points_mat.cwiseAbs()).colwise() - (*d).col(num_points); + // Eigen::Vector4f cost_vec = + // transfomed_cost_ary.cwiseMax(0).rowwise().sum(); + Eigen::MatrixXf transfomed_points_mat; + + double cost = evaluateCost(H, (*d).topLeftCorner(4, num_points), (*d).col(num_points), + transfomed_points_mat); + // evaluateCost(H, (*d).topLeftCorner(4, num_points), (*d).col(num_points)); + + // double total_cost = 0; + // double costx =0 , costy =0, costz= 0; + + Eigen::Matrix transformed_x_ind = + (transfomed_points_mat.row(0).array() > box_width).cast() + -(transfomed_points_mat.row(0).array() < -box_width).cast(); // 1 x n + + Eigen::Matrix transformed_y_ind = + (transfomed_points_mat.row(1).array() > tag_size / 2).cast() + -(transfomed_points_mat.row(1).array() < -tag_size / 2).cast(); // 1 x n + + Eigen::Matrix transformed_z_ind = + (transfomed_points_mat.row(2).array() > tag_size / 2).cast() + -(transfomed_points_mat.row(2).array() < -tag_size / 2).cast(); // 1 x n + + Eigen::Matrix + transformed_points_ind(1, 3*(num_points)); // 1 x 3n + transformed_points_ind << transformed_x_ind, transformed_y_ind, transformed_z_ind; + + + + Eigen::VectorXf grad_eig = Eigen::VectorXf::Zero(6); + if (!grad.empty()) { + Eigen::MatrixXf dx_mat = Eigen::MatrixXf::Zero(6, num_points); + d_px_lie_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dx_mat); // 6 x n + + Eigen::MatrixXf dy_mat = Eigen::MatrixXf::Zero(6, num_points); + d_py_lie_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dy_mat); + + Eigen::MatrixXf dz_mat = Eigen::MatrixXf::Zero(6, num_points); + d_pz_lie_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dz_mat); + + Eigen::MatrixXf d_mat(6, 3*(num_points)); + d_mat << dx_mat, dy_mat, dz_mat; + // int nan_index; + // int col_num; + // for (int p = 0; p < 3*(num_points-1); ++p) { + // if (isnan(d_mat.row(3)(p))) { + // cout << "index " << p << " is nan" << endl; + // if ((p > (num_points-1)) && (p < 2*(num_points-1))) { + // col_num = p + 1 - num_points; + // cout << "col_num: " << col_num << endl; + // } + // std::cout << "coordinates: \n" + // << transfomed_points_mat.col(col_num) << std::endl; + + // std::cout << "dmat: \n" << d_mat.col(p) << endl; + // nan_index = p; + // exit(0); + // break; + // } + // } + // if (d_mat.array().isNaN()){ + // cout << "2: nan" << endl; + // exit(0); + // } + // cout << "dx row 3: " << dx_mat.row(3) << endl; + // cout << "dx row 4: " << dx_mat.row(4) << endl; + // cout << "dx row 5" << dx_mat.row(5) << endl; + // cout << "dy row 3: " << dy_mat.row(3) << endl; + // cout << "dy row 4: " << dy_mat.row(4) << endl; + // cout << "dy row 5" << dy_mat.row(5) << endl; + // cout << "dz row 3: " << dz_mat.row(3) << endl; + // cout << "dz row 4: " << dz_mat.row(4) << endl; + // cout << "dz row 5" << dz_mat.row(5) << endl; + + grad_eig = d_mat * transformed_points_ind.transpose(); + grad[0] = grad_eig[0]; + grad[1] = grad_eig[1]; + grad[2] = grad_eig[2]; + grad[3] = grad_eig[3]; + grad[4] = grad_eig[4]; + grad[5] = grad_eig[5]; + // std::cout << "gradients_new : " << grad[0] << " "< &x, + std::vector &grad, + void *func_data) { + // ROS_INFO_STREAM("Inside ComputeCost"); + // x[0-2] transaltion , x[3-5] euler + Eigen::MatrixXf* d = reinterpret_cast(func_data); + int num_points = d->cols() - 1; // last column is passed as boundary + + // for (int i = 0; i < num_points; ++i) { + // Eigen::Vector3f p((*d)(0, i), (*d)(1, i), (*d)(2, i)); + // if (isnan(p(0)) || isnan(p(1)) || isnan(p(2))) { + // std::cout << "nan idx1 : " << i << std::endl; + // } + // } + const double box_width = (*d)(0, num_points); + const double tag_size = (*d)(0, num_points) * 2; + + Eigen::Quaternion q = + Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) * + Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) * + Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + Eigen::Matrix4f H = Eigen::Matrix4f::Identity(4, 4); + H.topLeftCorner(3, 3) = q.matrix(); + H.topRightCorner(3, 1) << x[0], x[1], x[2]; + + + // Eigen::MatrixXf transfomed_points_mat = + // (H * (*d).topLeftCorner(4, num_points)); // 4 x n + + // Eigen::MatrixXf transfomed_cost_ary = + // (transfomed_points_mat.cwiseAbs()).colwise() - (*d).col(num_points); + // Eigen::Vector4f cost_vec = + // transfomed_cost_ary.cwiseMax(0).rowwise().sum(); + Eigen::MatrixXf transfomed_points_mat; + + double cost = evaluateCost(H, (*d).topLeftCorner(4, num_points), (*d).col(num_points), + transfomed_points_mat); + // evaluateCost(H, (*d).topLeftCorner(4, num_points), (*d).col(num_points)); + + // double total_cost = 0; + // double costx =0 , costy =0, costz= 0; + + Eigen::Matrix transformed_x_ind = + (transfomed_points_mat.row(0).array() > box_width).cast() + -(transfomed_points_mat.row(0).array() < -box_width).cast(); // 1 x n + + Eigen::Matrix transformed_y_ind = + (transfomed_points_mat.row(1).array() > tag_size / 2).cast() + -(transfomed_points_mat.row(1).array() < -tag_size / 2).cast(); // 1 x n + + Eigen::Matrix transformed_z_ind = + (transfomed_points_mat.row(2).array() > tag_size / 2).cast() + -(transfomed_points_mat.row(2).array() < -tag_size / 2).cast(); // 1 x n + + Eigen::Matrix + transformed_points_ind(1, 3*(num_points)); // 1 x 3n + transformed_points_ind << transformed_x_ind, transformed_y_ind, transformed_z_ind; + + + + Eigen::VectorXf grad_eig = Eigen::VectorXf::Zero(6); + if (!grad.empty()) { + Eigen::MatrixXf dx_mat = Eigen::MatrixXf::Zero(6, num_points); + d_px_euler_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dx_mat); // 6 x n + + Eigen::MatrixXf dy_mat = Eigen::MatrixXf::Zero(6, num_points); + d_py_euler_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dy_mat); + + Eigen::MatrixXf dz_mat = Eigen::MatrixXf::Zero(6, num_points); + d_pz_euler_mat( + transfomed_points_mat.row(0), + transfomed_points_mat.row(1), + transfomed_points_mat.row(2), x[3], x[4], x[5], + dz_mat); + + Eigen::MatrixXf d_mat(6, 3*(num_points)); + d_mat << dx_mat, dy_mat, dz_mat; + // int nan_index; + // int col_num; + // for (int p = 0; p < 3*(num_points-1); ++p) { + // if (isnan(d_mat.row(3)(p))) { + // cout << "index " << p << " is nan" << endl; + // if ((p > (num_points-1)) && (p < 2*(num_points-1))) { + // col_num = p + 1 - num_points; + // cout << "col_num: " << col_num << endl; + // } + // std::cout << "coordinates: \n" + // << transfomed_points_mat.col(col_num) << std::endl; + + // std::cout << "dmat: \n" << d_mat.col(p) << endl; + // nan_index = p; + // exit(0); + // break; + // } + // } + // if (d_mat.array().isNaN()){ + // cout << "2: nan" << endl; + // exit(0); + // } + // cout << "dx row 3: " << dx_mat.row(3) << endl; + // cout << "dx row 4: " << dx_mat.row(4) << endl; + // cout << "dx row 5" << dx_mat.row(5) << endl; + // cout << "dy row 3: " << dy_mat.row(3) << endl; + // cout << "dy row 4: " << dy_mat.row(4) << endl; + // cout << "dy row 5" << dy_mat.row(5) << endl; + // cout << "dz row 3: " << dz_mat.row(3) << endl; + // cout << "dz row 4: " << dz_mat.row(4) << endl; + // cout << "dz row 5" << dz_mat.row(5) << endl; + + grad_eig = d_mat * transformed_points_ind.transpose(); + grad[0] = grad_eig[0]; + grad[1] = grad_eig[1]; + grad[2] = grad_eig[2]; + grad[3] = grad_eig[3]; + grad[4] = grad_eig[4]; + grad[5] = grad_eig[5]; + // std::cout << "gradients_new : " << grad[0] << " "< 0: \n" << (result.array() > 0 ) << endl; + // cout << "ans.cwisemax(0): \n" << result.array().cwiseMax(0) << endl; + // cout << "ans.cwisemax(0).sum: \n" << result.array().cwiseMax(0).rowwise().sum() << endl; + // exit(0); + // Eigen::Matrix4d test; + // test << 1, -2, 3, -4, // 4 + // -2, 3, -4, 5, // 8 + // -3, -4, -5, 6, // 6 + // 4, -5, -6, 7; // 11 + // int test_num = test.cols(); + // Eigen::Matrix test1 = + // (test.row(0).array() > 1).cast() - (test.row(0).array() < -1).cast(); + // Eigen::Matrix test2 = + // (test.row(1).array() > 1).cast() - (test.row(1).array() < -1).cast(); + // Eigen::Matrix test3 = + // (test.row(2).array() > 1).cast() - (test.row(2).array() < -1).cast(); + // Eigen::Matrix test_ind(1, 3*(test_num)); // 1 x 3n + // test_ind << test1, test2, test3; + + // cout << "test: \n" << test << endl; + // cout << "test.row(0) indx: " << test1 << endl;; + // cout << "test.row(1) indx: " << test2 << endl;; + // cout << "test.row(2) indx: " << test3 << endl;; + // cout << "conca test_ind: " << test_ind << endl;; + // exit(0); + + // Used for debug cost func + // for(int i =0; i< (num_points-1); ++i){ + // Eigen::Vector3d q(transfomed_points_mat.col(i)(0), transfomed_points_mat.col(i)(1), transfomed_points_mat.col(i)(2)); + // costx += checkCost(q[0], -box_width, box_width ); + // costy += checkCost(q[1], -(tag_size)/2, (tag_size)/2); + // costz += checkCost(q[2], -(tag_size)/2, (tag_size)/2); + // } + // total_cost = costx + costy + costz; + + // cout << "transformed_points_ind cols: " << transformed_points_ind.cols() << endl; + // cout << "ind: " << transformed_points_ind << endl; + + // for (int i = 0; i < 3*(num_points-1); ++i) { + // if (isnan(transformed_points_ind(i))) { + // std::cout << "nan idx1 : " << i << std::endl; + // } + // } + // exit(0); + + + // Eigen::MatrixXf test = Eigen::MatrixXf::Ones(1, 10); + // Eigen::MatrixXf test1 = Eigen::MatrixXf::Ones(1, 10); + // test1(0,1) = 10; + // test1(0,4) = 5; + // test(0,1) = 2; + // test(0,5) = 4; + // test(0,7) = 8; + // // Eigen::Matrix test_result = -(test.row(0).array() < 1).cast(); + // std::cout << "test result : " << test << std::endl; + // std::cout << "test1 result : " << test1 << std::endl; + // std::cout << "test multily result : " << (test*test1) << std::endl; + + + // // Eigen::VectorXf grad_eig = Eigen::VectorXf::Zero(6); + // grad_eig = Eigen::VectorXd::Zero(6); + // // if (!grad.empty()) { + // for(int i = 0; i < num_points - 1; ++i){ + // // Eigen::Vector3f p((*d)(0, i), (*d)(1, i), (*d)(2, i)); + // // Eigen::Vector3f q_pre = + // // H.topLeftCorner(3, 3) * p + H.topRightCorner(3, 1); + // Eigen::Vector4d q = transfomed_points_mat.col(i); + // // cout << "q: " << q_pre << endl; + // // cout << "q_mat: " << q << endl; + // // std::this_thread::sleep_for(std::chrono::milliseconds(5000)); + // // std::exit(0); + // Eigen::VectorXd d_px(6); + // d_px= d_px_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + + // Eigen::VectorXd d_py(6); + // d_py= d_py_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + // // if ((i+num_points-1) == nan_index) { + // // std::cout << "d_py : " << d_py << std::endl; + // // std::cout << "d_py_new : " << dy_mat.col(i) << std::endl; + // // std::cout << "d_mat : " << d_mat.col(i+num_points - 1) << std::endl; + // // std::cout << "coordinates:" << q << std::endl; + // // std::cout << "tag size:" << tag_size << std::endl; + // // } + // Eigen::VectorXd d_pz(6); + // d_pz= d_pz_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + + // // std::cout << "d_pz : " << d_pz << std::endl; + // // std::cout << "d_pz_new : " << dz_mat.col(i) << std::endl; + // // std::cout << "d_mat : " << d_mat.col(i+2*(num_points - 1)) << std::endl; + // if (q[0] > box_width) { + // grad_eig = (grad_eig + d_px).eval(); + // // std::cout << "d_px : " << d_px << std::endl; + // // std::cout << "d_px_new : " << dx_mat.col(i) << std::endl; + // // std::cout << "d_mat : " << d_mat.col(i) << std::endl; + // } else if (q[0] < -box_width) { + // grad_eig = (grad_eig - d_px).eval(); + // } + // if (q[1] > (tag_size)/2) { + // grad_eig = (grad_eig + d_py).eval(); + // } else if (q[1] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_py).eval(); + // } + // if (q[2] > (tag_size)/2) { + // grad_eig = (grad_eig + d_pz).eval(); + // } else if (q[2] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_pz).eval(); + // } + // } + // grad[0] = grad_eig[0]; + // grad[1] = grad_eig[1]; + // grad[2] = grad_eig[2]; + // grad[3] = grad_eig[3]; + // grad[4] = grad_eig[4]; + // grad[5] = grad_eig[5]; + // std::cout << "gradients : " << grad[0] << " "< &x, + // std::vector &grad, + // void *func_data) { + // // x[0-2] transaltion , x[3-5] euler + // Eigen::MatrixXf* d = reinterpret_cast(func_data); + // int num_points = d->cols(); + // const double box_width = 0.02; + // const double tag_size = (*d)(0, num_points-1); //0.02 + + // Eigen::Quaternion q = + // Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) * + // Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) * + // Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + // Eigen::Matrix4f H = Eigen::Matrix4f::Identity(4, 4); + // H.topLeftCorner(3, 3) = q.matrix(); + // H.topRightCorner(3, 1) << x[0], x[1], x[2]; + + // Eigen::Array4f template_bound; + // template_bound << box_width, tag_size / 2, tag_size / 2, 0; + // Eigen::MatrixXf transfomed_points_mat = + // H * (*d).topLeftCorner(4, num_points-1); + // Eigen::ArrayXf transfomed_cost_ary = + // transfomed_points_mat.array().abs() - template_bound; + // Eigen::Vector4f cost_vec = + // transfomed_cost_ary.cwiseMax(0).rowwise().sum(); + // double cost_x = cost_vec[0]; + // double cost_y = cost_vec[1]; + // double cost_z = cost_vec[2]; + + // if (!grad.empty()) { + // tbb::concurrent_vector grad_tbb(6); + // tbb::parallel_for(int(0), num_points - 1, [&](int i){ + // //for(int i = 0; i < num_points - 1; ++i){ + // Eigen::VectorXf grad_eig = Eigen::VectorXf::Zero(6); + // Eigen::Vector4f q = transfomed_points_mat.col(i); + // Eigen::VectorXf d_px(6); + // d_px= d_px_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + // Eigen::VectorXf d_py(6); + // d_py= d_py_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + // Eigen::VectorXf d_pz(6); + // d_pz= d_pz_euler(q[0], q[1], q[2], x[3], x[4], x[5]); + // if (q[0] > box_width) { + // grad_eig = (grad_eig + d_px).eval(); + // } else if (q[0] < -box_width) { + // grad_eig = (grad_eig - d_px).eval(); + // } + // if (q[1] > (tag_size)/2) { + // grad_eig = (grad_eig + d_py).eval(); + // } else if (q[1] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_py).eval(); + // } + // if (q[2] > (tag_size)/2) { + // grad_eig = (grad_eig + d_pz).eval(); + // } else if (q[2] < -(tag_size)/2) { + // grad_eig = (grad_eig - d_pz).eval(); + // } + + // for (int j = 0; j < 6; ++j) { + // grad_tbb[j] = grad_tbb[j] + grad_eig[j]; + // } + // //} + // }, tbb::auto_partitioner()); + // grad[0] = grad_tbb[0]; + // grad[1] = grad_tbb[1]; + // grad[2] = grad_tbb[2]; + // grad[3] = grad_tbb[3]; + // grad[4] = grad_tbb[4]; + // grad[5] = grad_tbb[5]; + // std::cout << "gradients : " << grad[0] << " "< x(6); + // x[0] = cluster.initial_pose.translation[0]; + // x[1] = cluster.initial_pose.translation[1]; + // x[2] = cluster.initial_pose.translation[2]; + // x[3] = cluster.initial_pose.roll; + // x[4] = cluster.initial_pose.pitch; + // x[5] = cluster.initial_pose.yaw; + + // //x, y, z, r, p, y + // std::vector lb(6), ub(6); + // lb[0] = x[0] - 15; //in meters + // lb[1] = x[1] - 8; + // lb[2] = x[2] - 2; + // lb[3] = x[3] - 1.57;//in rad (180 deg) + // lb[4] = x[4] - 1.57; + // lb[5] = x[5] - 1.57; + + // ub[0] = x[0] + 15; + // ub[1] = x[1] + 8; + // ub[2] = x[2] + 2; + // ub[3] = x[3] + 1.57; + // ub[4] = x[4] + 1.57; + // ub[5] = x[5] + 1.57; + + // // last column saved as other information such as tagsizes + // int num_points = cluster.merged_data.size(); + // Eigen::MatrixXf data = + // Eigen::MatrixXf::Ones(4, num_points + 1); + // data.block(0, 0, 3, num_points) = cluster.merged_data.topRows(3); + // data(0, num_points) = cluster.tag_size; + + // // pcl::PointCloud data = cluster.data; + // // pcl::PointCloud edge_points = cluster.edge_points; + // // data.reserve(data.size() + edge_points.size()); + // // data.insert(data.end(), edge_points.begin(), edge_points.end()); + // // edge_points.clear(); + // // LiDARPoints_t p; + // // p.tag_size = cluster.tag_size; + // // data.push_back(p); + // opt.set_lower_bounds(lb); + // opt.set_upper_bounds(ub); + // // opt.set_min_objective(costfunc_pre, &data); + // // opt.set_min_objective(costfunc, &data); + // opt.set_min_objective(computeCost, &data); + // opt.set_xtol_rel(1e-5); + // double minf; + + // try{ + // nlopt::result result = opt.optimize(x, minf); + // Eigen::Quaternion q = + // Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) * + // Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) * + // Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + // if (_debug_info) { + // std::cout << "optimzed euler angle : " + // << x[3]*180/M_PI << " " + // << x[4]*180/M_PI << " " + // << x[5]*180/M_PI << std::endl; + // } + // + // Eigen::Matrix3f rotation = q.matrix(); + + // Eigen::Vector3f translation(x[0], x[1], x[2]); + // Eigen::Matrix4f homogeneous; + // homogeneous.topLeftCorner(3,3) = rotation; + // homogeneous.topRightCorner(3,1) = translation; + // homogeneous.row(3) << 0,0,0,1; + + // cluster.pose_tag_to_lidar.homogeneous = homogeneous; + // cluster.pose_tag_to_lidar.translation = translation; + // cluster.pose_tag_to_lidar.rotation = rotation; + // // std::cout << "found minimum at f(" << x[0] << "," << x[1] << "," << x[2] << ") = " + // // << std::setprecision(10) << minf << std::endl; + // if (_debug_info) { + // std::cout << "found minimum at \n" << homogeneous << "\n the cost is: " + // << std::setprecision(10) << minf << std::endl; + // } + + // } + // catch(std::exception &e) { + // if (_debug_info) { + // std::cout << "nlopt failed: " << e.what() << std::endl; + // } + // } + // if (minf > _optimization_percent * cluster.inliers / 100) { + // return false; + // } else { + // return true; + // } + // } + + // return + // 3 if optimization failed, use initial pose + // 2 if optimization diverged, use initial pose + // 1 if successful + // -1 if rejected by initial guess + // -2 if rejected by coverage of area + // -3 initial guess is bad and optimization diverged + // -4 initial guess is bad and optimization failed + int LiDARTag::_optimizePose(ClusterFamily_t &cluster){ + int num_points = cluster.merged_data.cols(); + // box_width, tag size + Eigen::Vector4f template_bound( + 0.02, cluster.tag_size / 2, cluster.tag_size / 2, 0); // 4 x 1 + + Eigen::MatrixXf transformed_points; // 4 x n + double initial_cost = + evaluateCost(cluster.initial_pose.homogeneous, + cluster.merged_data_h, template_bound, transformed_points); + int status = 1; + + if (_debug_info) { + ROS_DEBUG_STREAM("==== _optimizePose ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + ROS_DEBUG_STREAM("Inital Cost: " << initial_cost); + ROS_DEBUG_STREAM("Cost Threshold: " << + _optimization_percent * cluster.inliers/100); + } + + if (initial_cost > _optimization_percent * cluster.inliers/100) { + status = -1; + ROS_DEBUG_STREAM("Status: " << status); + + return status; + } + + // compute convex hull and its area + Eigen::MatrixXf convex_hull; + utils::constructConvexHull(transformed_points, convex_hull); + float initial_area = utils::computePolygonArea(convex_hull); + float coverage_area = initial_area / (cluster.tag_size * cluster.tag_size); + // float coa_tunable = 0.75; + if (coverage_area < _coa_tunable) { + status = -2; + ROS_DEBUG_STREAM("Status: " << false); + + return status; + } + + + //initial guess + std::vector x(6); + x[0] = cluster.initial_pose.translation[0]; + x[1] = cluster.initial_pose.translation[1]; + x[2] = cluster.initial_pose.translation[2]; + if (_derivative_method) { + x[3] = cluster.initial_pose.roll; + x[4] = cluster.initial_pose.pitch; + x[5] = cluster.initial_pose.yaw; + } else { + Eigen::Vector3d lie_algebra = utils::Log_SO3(cluster.initial_pose.rotation); + x[3] = lie_algebra[0]; + x[4] = lie_algebra[1]; + x[5] = lie_algebra[2]; + } + + + + //x, y, z, r, p, y + std::vector lb(6), ub(6); + // double rpy_lb = 0.8; + // double rpy_ub = 0.8; + lb[0] = x[0] - 0.2; //in meters + lb[1] = x[1] - 0.2; + lb[2] = x[2] - 0.2; + lb[3] = x[3] - _opt_lb; // 1.57 in rad (180 deg) + lb[4] = x[4] - _opt_lb; + lb[5] = x[5] - _opt_lb; + + ub[0] = x[0] + 0.2; + ub[1] = x[1] + 0.2; + ub[2] = x[2] + 0.2; + ub[3] = x[3] + _opt_ub; + ub[4] = x[4] + _opt_ub; + ub[5] = x[5] + _opt_ub; + + + + // Numerical gradient methods + // good: LN_PRAXIS LN_NEWUOA_BOUND LN_SBPLX + // medium: LN_BOBYQA LN_NELDERMEAD + // bad: LN_COBYLA + // nlopt::opt opt(nlopt::LN_SBPLX, 6); + + // Analytical gradient methods + // LD_SLSQP LD_MMA + // LD_TNEWTON_PRECOND_RESTART + // LD_TNEWTON_PRECOND + // LD_TNEWTON_RESTART + // LD_TNEWTON + + nlopt::algorithm opt_method; + switch (_optimization_solver) { + // Below is numerical gradient-based methods + case 1: + opt_method = nlopt::LN_PRAXIS; + break; + case 2: + opt_method = nlopt::LN_NEWUOA_BOUND; + break; + case 3: + opt_method = nlopt::LN_SBPLX; // recommended + break; + case 4: + opt_method = nlopt::LN_BOBYQA; + break; + case 5: + opt_method = nlopt::LN_NELDERMEAD; + break; + case 6: + opt_method = nlopt::LN_COBYLA; + break; + // Below is analytical gradient-based methods + case 7: + opt_method = nlopt::LD_SLSQP; // recommended 200Hz + break; + case 8: + opt_method = nlopt::LD_MMA; // recommended 120Hz + break; + case 9: + opt_method = nlopt::LD_TNEWTON_PRECOND_RESTART; // fail 90% + break; + case 10: + opt_method = nlopt::LD_TNEWTON_PRECOND; // fail 90% + break; + case 11: + opt_method = nlopt::LD_TNEWTON_RESTART; // fail 80% + break; + case 12: + opt_method = nlopt::LD_TNEWTON; // fail 90% + break; + case 13: + opt_method = nlopt::LD_LBFGS; // fail 90% + break; + case 14: + opt_method = nlopt::LD_VAR1; // fail 90% + break; + case 15: + opt_method = nlopt::LD_VAR2; // fail 90% + break; + default: + opt_method = nlopt::LD_SLSQP; // recommended + } + + //initial guess + // std::vector x(6); + // x[0] = cluster.initial_pose.translation[0]; + // x[1] = cluster.initial_pose.translation[1]; + // x[2] = cluster.initial_pose.translation[2]; + // x[3] = cluster.initial_pose.roll; + // x[4] = cluster.initial_pose.pitch; + // x[5] = cluster.initial_pose.yaw; + // Eigen::Quaternion q = + // Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) * + // Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) * + // Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + + + // Eigen::Matrix3f rotation_old = q.matrix(); + // Eigen::Matrix3d rotation = rotation_from_euler(x[3],x[4],x[5]); + // cout << "homogeneous: \n" << cluster.initial_pose.homogeneous << endl; + // cout << "rpy_old: \n" << rotation_old << endl; + // cout << "rpy: \n" << rotation << endl; + // exit(0); + //x, y, z, r, p, y + // std::vector lb(6), ub(6); + // lb[0] = x[0] - 15; //in meters + // lb[1] = x[1] - 8; + // lb[2] = x[2] - 2; + // lb[3] = x[3] - 1.57; //in rad (180 deg) + // lb[4] = x[4] - 1.57; + // lb[5] = x[5] - 1.57; + + // ub[0] = x[0] + 15; + // ub[1] = x[1] + 8; + // ub[2] = x[2] + 2; + // ub[3] = x[3] + 1.57; + // ub[4] = x[4] + 1.57; + // ub[5] = x[5] + 1.57; + + // last column saved as other information such as tagsizes + // Eigen::Vector4f info_for_cost_function; + // info_for_cost_function << cluster.tag_size, 0, 0, 0; + Eigen::MatrixXf data(4, num_points + 1); + data << cluster.merged_data_h, template_bound; + + // XXX: tolerance and timeout + float x_tol = 1e-5; + double max_time = 1.0/15; // 15 Hz + double minf; + + nlopt::opt opt(opt_method, 6); + opt.set_lower_bounds(lb); + opt.set_upper_bounds(ub); + opt.set_xtol_rel(x_tol); + std::vector steps = + {0.01, 0.01, 0.01, 0.01, 0.01, 0.01}; // tx, ty, tz, r, p, y + opt.set_default_initial_step(steps); + if (_derivative_method) { + opt.set_min_objective(computeCost_euler, &data); + } else { + opt.set_min_objective(computeCost_lie, &data); + } + + // opt.set_maxtime(max_time); + + // [Error Code] + // https://github.com/stevengj/nlopt/blob/ + // 2f1fa1cc5f8a3f79834de9d155d5b6ef98aa7e50/src/api/nlopt.h#L162 + // NLOPT_FAILURE = -1, /* generic failure code */ + // NLOPT_INVALID_ARGS = -2, + // NLOPT_OUT_OF_MEMORY = -3, + // NLOPT_ROUNDOFF_LIMITED = -4, + // NLOPT_FORCED_STOP = -5, + // NLOPT_SUCCESS = 1, /* generic success code */ + // NLOPT_STOPVAL_REACHED = 2, + // NLOPT_FTOL_REACHED = 3, + // NLOPT_XTOL_REACHED = 4, + // NLOPT_MAXEVAL_REACHED = 5, + // NLOPT_MAXTIME_REACHED = 6, + + try{ + nlopt::result result = opt.optimize(x, minf); + + // if (result != 1) { + // nlopt_result results_nlopt = static_cast(result); + // ROS_WARN_STREAM("Optimization result: " << nlopt_result_to_string(results_nlopt)); + + // return false; // timeout + // } + if (minf > _optimization_percent * cluster.inliers / 1000) { + status = -3; + if (_debug_info) { + ROS_WARN_STREAM("Optimized Cost too large: " + << std::setprecision(3) << minf); + ROS_WARN_STREAM("Inital Cost: " << initial_cost); + } + if (initial_cost < 0.1 * _optimization_percent * cluster.inliers / 1000) { + status = 2; + if (_debug_info) { + ROS_WARN_STREAM("Use initial pose."); + } + + cluster.pose_tag_to_lidar.homogeneous = + cluster.initial_pose.homogeneous; + cluster.pose_tag_to_lidar.translation = + cluster.initial_pose.homogeneous.topRightCorner(3,1); + cluster.pose_tag_to_lidar.rotation = + cluster.initial_pose.homogeneous.topLeftCorner(3,3); + } + + return status; + } + + Eigen::Matrix3f rotation; + if (_derivative_method) { + Eigen::Quaternion q = + Eigen::AngleAxisf(x[3], Eigen::Vector3f::UnitX()) + * Eigen::AngleAxisf(x[4], Eigen::Vector3f::UnitY()) + * Eigen::AngleAxisf(x[5], Eigen::Vector3f::UnitZ()); + rotation = q.matrix(); + } else { + Eigen::Vector3d q(x[3], x[4], x[5]); + rotation = utils::Exp_SO3(q); + } + + + if (_debug_info) { + if (_derivative_method) { + ROS_DEBUG_STREAM("Optimzed euler angle : " + << x[3]*180/M_PI << ", " + << x[4]*180/M_PI << ", " + << x[5]*180/M_PI); + } else { + ROS_DEBUG_STREAM("Optimzed lie algebra : " + << x[3]<< ", " + << x[4] << ", " + << x[5]); + } + + } + Eigen::Vector3f translation(x[0], x[1], x[2]); + Eigen::Matrix4f homogeneous; + homogeneous.topLeftCorner(3,3) = rotation; + homogeneous.topRightCorner(3,1) = translation; + homogeneous.row(3) << 0,0,0,1; + + cluster.pose_tag_to_lidar.homogeneous = homogeneous; + cluster.pose_tag_to_lidar.translation = homogeneous.topRightCorner(3,1); + cluster.pose_tag_to_lidar.rotation = homogeneous.topLeftCorner(3,3); + // std::cout << "found minimum at f(" << x[0] << "," << x[1] << "," << x[2] << ") = " + // << std::setprecision(10) << minf << std::endl; + + if (_debug_info) { + nlopt_result results_nlopt = static_cast(result); + ROS_DEBUG_STREAM("Optimization result: " << std::string(nlopt_result_to_string(results_nlopt))); + ROS_DEBUG_STREAM("Optimized cost is: " << std::setprecision(3) << minf); + ROS_DEBUG_STREAM("Found minimum at \n" << homogeneous); + } + } + catch(std::exception &e) { + status = -4; + if (_debug_info) + ROS_WARN_STREAM("Pose optimization failed: " << e.what()); + if (initial_cost < 0.1 * _optimization_percent * cluster.inliers / 1000) { + status = 3; + cluster.pose_tag_to_lidar.homogeneous = + cluster.initial_pose.homogeneous; + cluster.pose_tag_to_lidar.translation = + cluster.initial_pose.homogeneous.topRightCorner(3,1); + cluster.pose_tag_to_lidar.rotation = + cluster.initial_pose.homogeneous.topLeftCorner(3,3); + if (_debug_info) + ROS_WARN_STREAM("Use initial pose."); + } + } + + if (_debug_info) { + ROS_DEBUG_STREAM("Status: " << status); + } + + return status; + } +}// namespace diff --git a/src/lidartag_prune.cc b/src/lidartag_prune.cc new file mode 100644 index 0000000..285cf1a --- /dev/null +++ b/src/lidartag_prune.cc @@ -0,0 +1,256 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include // package + +#include "ultra_puck.h" +#include "lidartag.h" + +#define SQRT2 1.41421356237 + +using namespace std; + +namespace BipedLab { + + /* + * A valid cluster, valid tag, the points from the original point cloud that belong to the cluster + * could be estimated from the LiDAR system + * Therefore, if the points on the tag is too less, which means it is not a valid + * tag where it might just a shadow of a valid tag + */ + bool LiDARTag::_clusterPointsCheck(ClusterFamily_t &Cluster){ + + auto distance = sqrt(pow(Cluster.average.x,2) + pow(Cluster.average.y,2)); + // cout << "distance: " << distance << "X: " << Cluster.average.x << "Y: " << Cluster.average.y << endl; + int maxPoints = LiDARTag::_areaPoints(distance, _payload_size*SQRT2, _payload_size*SQRT2); + int minPoints = LiDARTag::_areaPoints(distance, _payload_size/SQRT2, _payload_size/SQRT2); + // cout << "Cluster Size: " << Cluster.data.size() << " Max Points: " << maxPoints << " Min Points: " << minPoints << endl; + //cout << "Data: " << Cluster.data.size() << endl; + // return true; + // if (Cluster.data.size() < floor(points/ _points_threshold_factor)) return false; + // else return true; + + if (Cluster.data.size() < minPoints) { // Cluster.data.size() > maxPoints) { // || Cluster.data.size() < minPoints) { + return false; + } else { + return true; + } + } + + /* + * A function to get a number of points on a given-distance tag or object + */ + int LiDARTag::_areaPoints(const double &Distance, const double &ObjWidth, const double &ObjHeight){ + // double WAngle = ObjWidth * (1 + SQRT2) / abs(Distance); + + // if (WAngle>=1) return (int) 1e6; // return big number to reject the cluster + + // double HAngle = ObjHeight * (1 + SQRT2) / abs(Distance); + // if (HAngle>=1) return (int) 1e6; // return big number to reject the cluster + + // double HorizontalAngle = asin(WAngle); // in radian + // double VerticalAngle = asin(HAngle); // in radian + // int NumOfVerticalRing = floor(VerticalAngle * _LiDAR_system.beam_per_vertical_radian); + // int NumOfHorizontalPoints = floor(HorizontalAngle * _LiDAR_system.point_per_horizontal_radian); + + // // use 3 instead of 2 becasue of we assume the tag would be put in the dense + // // region of LiDAR (LiDAR is denser in the middle) + // int Area = floor(3 * (NumOfVerticalRing * NumOfHorizontalPoints) / (1 + SQRT2)); + + // cout << "distance: " << Distance << endl; + // //cout << "HorizontalAngle: " << HorizontalAngle << endl; + // //cout << "VerticalAngle: " << VerticalAngle << endl; + + int NumOfHorizontalPoints = ceil(ObjWidth / (Distance * tan(0.1 * M_PI / 180))); + + + //int NumOfHorizontalPoints = 2 * atan((ObjWidth / 2) / abs(Distance)) * + // _LiDAR_system.point_per_horizontal_radian; + double HalfVerticalAngle = atan((ObjHeight / 2) / abs(Distance)) * 180 / M_PI; + + int NumOfVerticalRing = 0; + for (int i = 0; i < UltraPuckV2::beams; ++i) + { + if (HalfVerticalAngle > abs(UltraPuckV2::el[i])) + { + NumOfVerticalRing++; + } + } + int Area = NumOfVerticalRing * NumOfHorizontalPoints; + + // cout << "NumOfVerticalRing: " << NumOfVerticalRing << endl; + // cout << "NumOfHorizontalPoints: " << NumOfHorizontalPoints << endl; + // cout << "Area: " << Area << endl; + // cout << "Points / Radian: " << _LiDAR_system.point_per_horizontal_radian << endl; + + return Area; + } + + /* + * A function to calculate the upper bound of points that can exist in a cluster + * based on the payload size + */ + void LiDARTag::_maxPointsCheck(ClusterFamily_t &cluster) { + int ring = std::round(_beam_num / 2); + double point_resolution = 2 * M_PI / _LiDAR_system.ring_average_table[ring].average; + auto distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + float payload_w = SQRT2 * _payload_size; + int num_horizontal_points = std::ceil(payload_w / (distance * std::sin(point_resolution))); + int num_vertical_ring = std::abs(cluster.top_ring - cluster.bottom_ring) + 1; + + // float point_resolution = 0.1 * M_PI/180; + // auto distance = sqrt(pow(cluster.average.x,2) + pow(cluster.average.y,2)); + // // auto payload_w = 2*SQRT2*_payload_size; + // // auto payload_h = 2*SQRT2*_payload_size; + // auto payload_w = SQRT2 * _payload_size; + // auto payload_h = SQRT2 * _payload_size; + // + // int num_horizontal_points = + // std::ceil(payload_w / (distance * tan(point_resolution))); + // double HalfVerticalAngle = + // std::atan((payload_h / 2) / abs(distance)) * 180 / M_PI; + + // int num_vertical_ring = 0; + // for (int i = 0; i < UltraPuckV2::beams; ++i) + // { + // if (HalfVerticalAngle > abs(UltraPuckV2::el[i])) + // { + // num_vertical_ring++; + // } + // } + + int expected_points = num_vertical_ring * num_horizontal_points; + + + if ((cluster.data.size() + cluster.edge_points.size()) > expected_points) { + _result_statistics.cluster_removal.maximum_return ++; + _result_statistics.remaining_cluster_size--; + if (_mark_cluster_validity) + cluster.valid = false; + } + + if (_debug_info) { + ROS_DEBUG_STREAM("==== _maxPointsCheck ===="); + ROS_DEBUG_STREAM("Distance : " << distance << ", num_horizontal_points: " << num_horizontal_points); + ROS_DEBUG_STREAM("Expected Points: " << expected_points); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + if ((cluster.data.size() + cluster.edge_points.size()) > expected_points) + ROS_DEBUG_STREAM("Status: " << false); + else + ROS_DEBUG_STREAM("Status: " << true); + } + } + + /* + * Fit a plane to a cluster. Returns false if unable to estimate a plane. + * Otherwise, returns the number of inliers and the coefficients of the plane. + */ + bool LiDARTag::_rejectWithPlanarCheck( + ClusterFamily_t &cluster, + pcl::PointIndices::Ptr inliers, + pcl::ModelCoefficients::Ptr coefficients, + std::ostream &fplanefit) { + + // Convert cluster family into pcl point cloud + pcl::PointCloud::Ptr cloud(new pcl::PointCloud); + cloud->points.resize(cluster.data.size()+cluster.edge_points.size()); + for (std::size_t i = 0; i < cluster.edge_points.size(); ++i) { + cloud->points[i].x = cluster.edge_points[i].point.x; + cloud->points[i].y = cluster.edge_points[i].point.y; + cloud->points[i].z = cluster.edge_points[i].point.z; + } + for (std::size_t i = cluster.edge_points.size(); i < cloud->points.size(); ++i) { + cloud->points[i].x = cluster.data[i - cluster.edge_points.size()].point.x; + cloud->points[i].y = cluster.data[i - cluster.edge_points.size()].point.y; + cloud->points[i].z = cluster.data[i - cluster.edge_points.size()].point.z; + } + + // Create segmentation object + pcl::SACSegmentation seg; + + // Optional + seg.setOptimizeCoefficients (true); + // Mandatory + seg.setModelType(pcl::SACMODEL_PLANE); + seg.setMethodType(pcl::SAC_RANSAC); + seg.setDistanceThreshold(_distance_to_plane_threshold); + + seg.setInputCloud(cloud); + seg.segment(*inliers, *coefficients); + cluster.inliers = inliers->indices.size(); + if (_debug_info) { + ROS_DEBUG_STREAM("==== _rejectWithPlanarCheck ===="); + float distance = + std::sqrt(pow(cluster.average.x, 2) + + pow(cluster.average.y, 2) + + pow(cluster.average.z, 2)); + ROS_DEBUG_STREAM("Distance : " << distance); + ROS_DEBUG_STREAM("Actual Points: " << cluster.data.size() + cluster.edge_points.size()); + ROS_DEBUG_STREAM("Inliers : " << inliers->indices.size()); + ROS_DEBUG_STREAM("Outliers : " << + cluster.data.size() - inliers->indices.size()); + } + if (inliers->indices.size() == 0) { + if (_debug_info) { + ROS_DEBUG_STREAM("Status: " << false); + ROS_WARN_STREAM("Failed to fit a plane model to the cluster."); + } + _result_statistics.cluster_removal.plane_fitting++; + _result_statistics.remaining_cluster_size--; + + return false; + } + + if (_debug_info) + ROS_DEBUG_STREAM("Status: " << true); + if (_log_data) { + fplanefit << "Successfully fit plane!" << endl; + fplanefit << "Cluster Size: " << cluster.data.size() << endl; + fplanefit << "Inliers : " << inliers->indices.size() << endl; + fplanefit << "Outliers : " << + cluster.data.size() - inliers->indices.size() << endl; + } + + return true; + } + +} diff --git a/src/lidartag_rviz.cc b/src/lidartag_rviz.cc new file mode 100644 index 0000000..99e8d54 --- /dev/null +++ b/src/lidartag_rviz.cc @@ -0,0 +1,949 @@ +/* Copyright (C) 2013-2020, The Regents of The University of Michigan. + * All rights reserved. + * This software was developed in the Biped Lab (https://www.biped.solutions/) + * under the direction of Jessy Grizzle, grizzle@umich.edu. This software may + * be available under alternative licensing terms; contact the address above. + * 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 Regents of The University of Michigan. + * + * AUTHOR: Bruce JK Huang (bjhuang@umich.edu) + * WEBSITE: https://www.brucerobot.com/ + */ + +#include + +#include // package +#include "lidartag.h" + +#include +#include + +using namespace std; + +namespace BipedLab { + + /* + * A function to draw a point in rviz + */ + void LiDARTag::_assignMarker(visualization_msgs::Marker &Marker, const uint32_t Shape, const string NameSpace, + const double r, const double g, const double b, + const PointXYZRI &point, + const int Count, const double Size, const string Text){ + Marker.header.frame_id = _pub_frame; + Marker.header.stamp = _current_scan_time; + Marker.ns = NameSpace; + Marker.id = Count; + Marker.type = Shape; + Marker.action = visualization_msgs::Marker::ADD; + Marker.pose.position.x = point.x; + Marker.pose.position.y = point.y; + Marker.pose.position.z = point.z; + Marker.pose.orientation.x = 0.0; + Marker.pose.orientation.y = 0.0; + Marker.pose.orientation.z = 0.0; + Marker.pose.orientation.w = 1.0; + Marker.text = Text; + Marker.lifetime = ros::Duration(_sleep_time_for_vis); // should disappear along with updateing rate + + // Set the scale of the marker -- 1x1x1 here means 1m on a side + Marker.scale.x = Size; + Marker.scale.y = Size; + Marker.scale.z = Size; + + // Set the color -- be sure to set alpha to something non-zero! + Marker.color.r = r; + Marker.color.g = g; + Marker.color.b = b; + Marker.color.a = 1.0; + } + + void LiDARTag::_assignVectorMarker(visualization_msgs::Marker &Marker, const uint32_t Shape, const string NameSpace, + const double r, const double g, const double b, + const int Count, const double Size, Eigen::Vector3f edge_vector, const PointXYZRI ¢riod, const string Text){ + // LiDARTag::_assignMarker(Marker, visualization_msgs::Marker::SPHERE, NameSpace, + // r, g, b, + // centriod, + // Count, Size, Text); + + // PointXYZRI p2; + // p2.x = centriod.x + edge_vector[0]; + // p2.y = centriod.y + edge_vector[1]; + // p2.z = centriod.z + edge_vector[2]; + // LiDARTag::_assignMarker(Marker, visualization_msgs::Marker::SPHERE, NameSpace, + // r, g, b, + // p2, + // Count+1, Size, Text); + + + + Marker.header.frame_id = _pub_frame; + Marker.header.stamp = _current_scan_time; + Marker.ns = NameSpace; + Marker.id = Count; + Marker.type = Shape; + Marker.action = visualization_msgs::Marker::ADD; + + Marker.text = Text; + Marker.lifetime = ros::Duration(_sleep_time_for_vis); // should disappear along with updateing rate + // Set the scale of the marker -- 1x1x1 here means 1m on a side + geometry_msgs::Point p1; + p1.x = 0; //centriod.x; + p1.y = 0; //centriod.y; + p1.z = 0; //centriod.z; + Marker.points.push_back(p1); + + geometry_msgs::Point p2; + p2.x = edge_vector[0]; + p2.y = edge_vector[1]; + p2.z = edge_vector[2]; + Marker.points.push_back(p2); + Marker.color.r = r; + Marker.color.g = g; + Marker.color.b = b; + Marker.scale.x = 0.02; + Marker.scale.y = Size; + Marker.scale.z = Size; + // Set the color -- be sure to set alpha to something non-zero! + + } + void LiDARTag::_plotIdealFrame(){ + visualization_msgs::MarkerArray FrameMarkArray; + for (int k =0; k < _tag_size_list.size(); ++k) { + visualization_msgs::Marker line_list; + line_list.id = 0; + line_list.header = _point_cloud_header; + line_list.type = visualization_msgs::Marker::LINE_LIST; + line_list.ns = "tag_size_" + to_string(_tag_size_list[k]); + line_list.color.g = 1.0; + line_list.color.a = 1.0; + line_list.scale.x = 0.01; + + vector> vertex = {{1,1},{1,-1},{-1,-1}, {-1,1}}; + for(int i = 0; i < 4; ++i){ + vector v = vertex[i]; + geometry_msgs::Point p; + p.x = -0.02; + p.y = v[0]*_tag_size_list[k]/2; //_payload_size + p.z = v[1]*_tag_size_list[k]/2; + line_list.points.push_back(p); + p.x = 0.02; + line_list.points.push_back(p); + } + + for(int j = -1; j<=1; j+=2){ + for(int i = 0; i < 4; ++i){ + vector v = vertex[i]; + geometry_msgs::Point p; + p.x = j* 0.02; + p.y = v[0]*_tag_size_list[k]/2; + p.z = v[1]*_tag_size_list[k]/2; + line_list.points.push_back(p); + v = vertex[(i+1)%4]; + p.y = v[0]*_tag_size_list[k]/2; + p.z = v[1]*_tag_size_list[k]/2; + line_list.points.push_back(p); + } + } + FrameMarkArray.markers.push_back(line_list); + } + + _ideal_frame_pub.publish(FrameMarkArray); + } + + // visualization_msgs::Marker line_list; + // line_list.id = 0; + // line_list.header = _point_cloud_header; + // line_list.type = visualization_msgs::Marker::LINE_LIST; + // line_list.color.g = 1.0; + // line_list.color.a = 1.0; + // line_list.scale.x = 0.01; + + // vector> vertex = {{1,1},{1,-1},{-1,-1}, {-1,1}}; + // for(int i = 0; i < 4; ++i){ + // vector v = vertex[i]; + // geometry_msgs::Point p; + // p.x = -0.02; + // p.y = v[0]*1.22/2; //_payload_size + // p.z = v[1]*1.22/2; + // line_list.points.push_back(p); + // p.x = 0.02; + // line_list.points.push_back(p); + // } + + // for(int j = -1; j<=1; j+=2){ + // for(int i = 0; i < 4; ++i){ + // vector v = vertex[i]; + // geometry_msgs::Point p; + // p.x = j* 0.02; + // p.y = v[0]*1.22/2; + // p.z = v[1]*1.22/2; + // line_list.points.push_back(p); + // v = vertex[(i+1)%4]; + // p.y = v[0]*1.22/2; + // p.z = v[1]*1.22/2; + // line_list.points.push_back(p); + // } + // } + + void LiDARTag::_plotTagFrame(const ClusterFamily_t &cluster){ + visualization_msgs::Marker line_list; + line_list.id = cluster.cluster_id; + line_list.header = _point_cloud_header; + line_list.type = visualization_msgs::Marker::LINE_LIST; + // line_list.ns = "tag_size_" + to_string(_tag_size_list[k]); + line_list.color.r = 0.0; + line_list.color.g = 1.0; + line_list.color.b = 1.0; + line_list.color.a = 1.0; + line_list.scale.x = 0.01; + + vector> vertex = {{1,1},{1,-1},{-1,-1}, {-1,1}}; + for(int i = 0; i < 4; ++i){ + vector v = vertex[i]; + Eigen::Vector4f corner_lidar1(-0.02, v[0]*cluster.tag_size/2, v[1]*cluster.tag_size/2, 1); + Eigen::Vector4f corner_lidar2(0.02, v[0]*cluster.tag_size/2, v[1]*cluster.tag_size/2, 1); + Eigen::Vector4f corner_tag1 = cluster.pose.homogeneous * corner_lidar1; + Eigen::Vector4f corner_tag2 = cluster.pose.homogeneous * corner_lidar2; + geometry_msgs::Point p; + p.x = corner_tag1(0); + p.y = corner_tag1(1); //_payload_size + p.z = corner_tag1(2); + line_list.points.push_back(p); + p.x = corner_tag2(0); + p.y = corner_tag2(1); //_payload_size + p.z = corner_tag2(2); + line_list.points.push_back(p); + } + + for(int j = -1; j<=1; j+=2){ + for(int i = 0; i < 4; ++i){ + vector v = vertex[i]; + Eigen::Vector4f corner_lidar1(j* 0.02, v[0]*cluster.tag_size/2, v[1]*cluster.tag_size/2, 1); + Eigen::Vector4f corner_tag1 = cluster.pose.homogeneous * corner_lidar1; + geometry_msgs::Point p; + p.x = corner_tag1(0); + p.y = corner_tag1(1); + p.z = corner_tag1(2); + line_list.points.push_back(p); + v = vertex[(i+1)%4]; + Eigen::Vector4f corner_lidar2(j* 0.02, v[0]*cluster.tag_size/2, v[1]*cluster.tag_size/2, 1); + Eigen::Vector4f corner_tag2 = cluster.pose.homogeneous * corner_lidar2; + p.x = corner_tag2(0); + p.y = corner_tag2(1); + p.z = corner_tag2(2); + line_list.points.push_back(p); + } + } + + _tag_frame_pub.publish(line_list); + } + + + visualization_msgs::Marker + LiDARTag::_visualizeVector( + Eigen::Vector3f edge_vector, + PointXYZRI centriod, + int ID){ + visualization_msgs::Marker edge; + edge.id = ID; + edge.header = _point_cloud_header; + edge.type = visualization_msgs::Marker::LINE_STRIP; + edge.color.g = 1.0; + edge.color.a = 1.0; + edge.scale.x = 0.02; + + geometry_msgs::Point p; + p.x = centriod.x; + p.y = centriod.y; + p.z = centriod.z; + edge.points.push_back(p); + + //edge_vector = (edge_vector*_payload_size).eval(); + p.x += edge_vector[0]; + p.y += edge_vector[1]; + p.z += edge_vector[2]; + edge.points.push_back(p); + + //_edge_vector_pub.publish(edge); + return edge; + } + /* + * A function to prepare for displaying results in rviz + */ + void LiDARTag::_clusterToPclVectorAndMarkerPublisher(const std::vector &Cluster, + pcl::PointCloud::Ptr OutCluster, + pcl::PointCloud::Ptr OutEdgeCluster, + pcl::PointCloud::Ptr OutPayload, + pcl::PointCloud::Ptr OutPayload3D, + pcl::PointCloud::Ptr OutTarget, + pcl::PointCloud::Ptr OutInitialTarget, + pcl::PointCloud::Ptr EdgeGroup1, + pcl::PointCloud::Ptr EdgeGroup2, + pcl::PointCloud::Ptr EdgeGroup3, + pcl::PointCloud::Ptr EdgeGroup4, + pcl::PointCloud::Ptr BoundaryPts, + visualization_msgs::MarkerArray &ClusterArray){ + + /* initialize random seed for coloring the marker*/ + srand (time(NULL)); + visualization_msgs::MarkerArray BoundMarkArray; + visualization_msgs::MarkerArray PayloadMarkArray; + visualization_msgs::MarkerArray IDMarkArray; + // Used to identify between multiple clusters in a single point + // cloud in the analysis file. The id being reset to 1 each time + // the function is called is supposed to indicate in the output + // file that the proceeding clusters belong to a new payload + int cluster_pc_id = 1; + + int PointsInClusters = 0; + + int Clustercount = 0; + for (int Key=0; Key0) ? + // // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + // geometry_msgs::Point start_point; + // geometry_msgs::Point end_point; + // start_point.x = Cluster[Key].average.x; + // start_point.y = Cluster[Key].average.y; + // start_point.z = Cluster[Key].average.z; + // BoundaryMarker.points.push_back(start_point); + // end_point.x = Cluster[Key].average.x + Cluster[Key].principal_axes.col(0)(0); + // end_point.y = Cluster[Key].average.y + Cluster[Key].principal_axes.col(0)(1); + // end_point.z = Cluster[Key].average.z + Cluster[Key].principal_axes.col(0)(2); + // BoundaryMarker.points.push_back(end_point); + // BoundaryMarker.pose.orientation.x = 0; + // BoundaryMarker.pose.orientation.y = 0; + // BoundaryMarker.pose.orientation.z = 0; + // BoundaryMarker.pose.orientation.w = 0; + // BoundMarkArray.markers.push_back(BoundaryMarker); + + // LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + // "NormalVector_y" + to_string(Cluster[Key].cluster_id), + // 0, 1, 0, + // Cluster[Key].average, 1, 0.01); + // BoundaryMarker.scale.x = 0; + // BoundaryMarker.scale.y = 0; + // BoundaryMarker.scale.z = 0; + // // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + // BoundaryMarker.points.push_back(start_point); + // end_point.x = Cluster[Key].average.x + Cluster[Key].principal_axes.col(1)(0); + // end_point.y = Cluster[Key].average.y + Cluster[Key].principal_axes.col(1)(1); + // end_point.z = Cluster[Key].average.z + Cluster[Key].principal_axes.col(1)(2); + // BoundaryMarker.points.push_back(end_point); + // BoundaryMarker.pose.orientation.x = 0; + // BoundaryMarker.pose.orientation.y = 0; + // BoundaryMarker.pose.orientation.z = 0; + // BoundaryMarker.pose.orientation.w = 0; + // BoundMarkArray.markers.push_back(BoundaryMarker); + + // LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + // "NormalVector_z" + to_string(Cluster[Key].cluster_id), + // 0, 0, 1, + // Cluster[Key].average, 1, 0.01); + // BoundaryMarker.scale.x = 0; + // BoundaryMarker.scale.y = 0; + // BoundaryMarker.scale.z = 0; + // // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + // BoundaryMarker.points.push_back(start_point); + // end_point.x = Cluster[Key].average.x + Cluster[Key].principal_axes.col(2)(0); + // end_point.y = Cluster[Key].average.y + Cluster[Key].principal_axes.col(2)(1); + // end_point.z = Cluster[Key].average.z + Cluster[Key].principal_axes.col(2)(2); + // BoundaryMarker.points.push_back(end_point); + // BoundaryMarker.pose.orientation.x = 0; + // BoundaryMarker.pose.orientation.y = 0; + // BoundaryMarker.pose.orientation.z = 0; + // BoundaryMarker.pose.orientation.w = 0; + // BoundMarkArray.markers.push_back(BoundaryMarker); + + /* + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector1" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector2" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector3" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector4" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector5" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector6" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + + LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::ARROW, + "NormalVector7" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + Cluster[Key].average, 1, 0.01); + BoundaryMarker.scale.x = 0.15; + // BoundaryMarker.pose.orientation.x = (Cluster[Key].normal_vector(0)>0) ? + // -Cluster[Key].normal_vector(0) : Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.x = Cluster[Key].normal_vector(0); + BoundaryMarker.pose.orientation.y = Cluster[Key].normal_vector(1); + BoundaryMarker.pose.orientation.z = Cluster[Key].normal_vector(2); + BoundaryMarker.pose.orientation.w = 0; + BoundMarkArray.markers.push_back(BoundaryMarker); + */ + + + + // LiDARTag::_assignMarker(BoundaryMarker, visualization_msgs::Marker::SPHERE, + // "Average" + to_string(Cluster[Key].cluster_id), + // r, g, b, + // Cluster[Key].average, 5, 0.04); + // BoundMarkArray.markers.push_back(BoundaryMarker); + + + + //_cluster_pub.publish(BoundaryMarkerList); + //LiDARTag::_assignLine(BoundaryMarkerList, visualization_msgs::Marker::LINE_STRIP, + // r, g, b, + // Cluster[Key], 1); + //_cluster_pub.publish(BoundaryMarkerList); + + // _boundary_marker_pub.publish(BoundMarkArray); + if (_id_decoding) { + visualization_msgs::Marker IDMarker; + LiDARTag::_assignMarker(IDMarker, visualization_msgs::Marker::TEXT_VIEW_FACING, + "Text" + to_string(Cluster[Key].cluster_id), + 1, 1, 1, + Cluster[Key].average, 1, Cluster[Key].tag_size*0.7, + string( + to_string(Cluster[Key].rkhs_decoding.id) + ) + ); + IDMarkArray.markers.push_back(IDMarker); + } + // Draw payload boundary marker + visualization_msgs::Marker PayloadMarker; + + if (_adaptive_thresholding){ + // Upper boundary + for (int i=0; ipoint, i, 0.015); + PayloadMarkArray.markers.push_back(PayloadMarker); + } + + // Lower boundary + for (int i=0; ipoint, i, 0.015); + PayloadMarkArray.markers.push_back(PayloadMarker); + } + + // Left boundary (green) + for (int i=0; ipoint, i, 0.015); + PayloadMarkArray.markers.push_back(PayloadMarker); + } + + // Right boundary (red) + for (int i=0; ipoint, i, 0.015); + PayloadMarkArray.markers.push_back(PayloadMarker); + } + } + else { + + // cout << "size1: " << Cluster[Key].payload_boundary_ptr.size() << endl; + int count = 0; + for (int i=0; ipoint, count, 0.015); + // PayloadMarkArray.markers.push_back(PayloadMarker); + // count ++; + + // LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::SPHERE, + // "PayloadBoundary_" + to_string(Cluster[Key].cluster_id), + // 1, 0, 0, + // Cluster[Key].payload_boundary_ptr[i][1]->point, count, 0.015); + // count ++; + // PayloadMarkArray.markers.push_back(PayloadMarker); + // } + // for (int k=0; kpoint, i, 0.015); + PayloadMarkArray.markers.push_back(PayloadMarker); + count ++; + // } + } + } + + // Text + /* + LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::TEXT_VIEW_FACING, + "PayloadUpperBoundary_text_" + to_string(Cluster[Key].cluster_id), + 1, 1, 1, + Cluster[Key].tag_edges.upper_line[0]->point, 5, 0.05, + string("Ring: " + to_string(Cluster[Key].tag_edges.upper_line[0]->point.ring)) + ); + PayloadMarkArray.markers.push_back(PayloadMarker); + + LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::TEXT_VIEW_FACING, + "PayloadLowerBoundary_text_" + to_string(Cluster[Key].cluster_id), + 1, 1, 1, + Cluster[Key].tag_edges.lower_line[0]->point, 5, 0.05, + string("Ring: " + to_string(Cluster[Key].tag_edges.lower_line[0]->point.ring)) + ); + PayloadMarkArray.markers.push_back(PayloadMarker); + */ + + + // corner points and RANSAC line + if (_adaptive_thresholding){ + Eigen::Vector4f EigenPoint; + PointXYZRI point; // just for conversion + + for (int i=0; i<4; ++i){ // 4 corners + // Corners + if (i!=3){ + pcl::lineWithLineIntersection(Cluster[Key].line_coeff[i], Cluster[Key].line_coeff[i+1], + EigenPoint, 1e-2); + } + else { + pcl::lineWithLineIntersection(Cluster[Key].line_coeff[i], Cluster[Key].line_coeff[0], + EigenPoint, 1e-2); + } + + LiDARTag::_eigenVectorToPointXYZRI(EigenPoint, point); + LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::SPHERE, + "Corner_" + to_string(Cluster[Key].cluster_id), + 0, 1, 1, + point, i, 0.02); + PayloadMarkArray.markers.push_back(PayloadMarker); + + // RANSAC + LiDARTag::_assignMarker(PayloadMarker, visualization_msgs::Marker::ARROW, + "RANSAC" + to_string(Cluster[Key].cluster_id), + 1, 1, 0, + point, i, 0.01); + double Length = sqrt(pow(Cluster[Key].line_coeff[i][3],2) + + pow(Cluster[Key].line_coeff[i][4],2) + + pow(Cluster[Key].line_coeff[i][5],2)); + PayloadMarker.scale.x = 0.15; + PayloadMarker.pose.orientation.x = Cluster[Key].line_coeff[i][3]/Length; + PayloadMarker.pose.orientation.y = Cluster[Key].line_coeff[i][4]/Length; + PayloadMarker.pose.orientation.z = Cluster[Key].line_coeff[i][5]/Length; + PayloadMarkArray.markers.push_back(PayloadMarker); + } + } + + // Add lines to the tag + //LiDARTag::_assignLine(PayloadMarker, PayloadMarkArray, + // visualization_msgs::Marker::LINE_STRIP, + // "left_line_" + to_string(Cluster[Key].cluster_id), + // r, g, b, + // PointTL, PointTR, 1); + //PayloadMarkArray.markers.push_back(PayloadMarker); + + // TODO: Too many for loops, could be done in a better way. + // Some of the loops are inside of the _detectionArrayPublisher + // Changes NEEDED! + + // Draw all detected-filled cluster points + + + for (int i=0; ipush_back(Cluster[Key].data[i].point); + + double Intensity = Cluster[Key].data[i].point.intensity; + LiDARTag::_assignMarker(Marker, visualization_msgs::Marker::SPHERE, + to_string(Cluster[Key].cluster_id), + Intensity, Intensity, Intensity, + Cluster[Key].data[i].point, i, 0.01); + ClusterArray.markers.push_back(Marker); + } + if (_mark_cluster_validity) { + for (int i=0; ipush_back(Cluster[Key].edge_points[i].point); + } + for (int i=0; ipush_back(Cluster[Key].edge_group1[i].point); + } + for (int i=0; ipush_back(Cluster[Key].edge_group2[i].point); + } + for (int i=0; ipush_back(Cluster[Key].edge_group3[i].point); + } + for (int i=0; ipush_back(Cluster[Key].edge_group4[i].point); + } + for(int ring=0; ring<_beam_num; ++ring){ + if (Cluster[Key].payload_right_boundary_ptr[ring]!=0) { + BoundaryPts->push_back(Cluster[Key].payload_right_boundary_ptr[ring]->point); + } + if (Cluster[Key].payload_left_boundary_ptr[ring]!=0) { + BoundaryPts->push_back(Cluster[Key].payload_left_boundary_ptr[ring]->point); + } + } + } + // Add all payload points to a vector and will be publish to another + // channel for both visualizatoin and creating training datasets + // cout << "payload size2: " << Cluster[Key].payload.size() << endl; + // for (int i=0; ipush_back(point); + // OutPayload->push_back(Cluster[Key].data[i].point); + // // cout << "Intensity: " << Cluster[Key].payload[i]->point.intensity << endl; + // } + + // for (int i=0; ipush_back(point); + // OutPayload->push_back(Cluster[Key].edge_points[i].point); + // // cout << "Intensity: " << Cluster[Key].payload[i]->point.intensity << endl; + // } + // ROS_INFO_STREAM("rows: " << Cluster[Key].rkhs_decoding.template_points_3d.rows()); + // ROS_INFO_STREAM("cols: " << Cluster[Key].rkhs_decoding.template_points_3d.cols()); + if (_id_decoding) { + for (int i=0; icols(); ++i){ + PointXYZRI point; + point.x = Cluster[Key].rkhs_decoding.associated_pattern_3d->col(i)(0); + point.y = Cluster[Key].rkhs_decoding.associated_pattern_3d->col(i)(1); + point.z = Cluster[Key].rkhs_decoding.associated_pattern_3d->col(i)(2); + if (point.x >= 0) { + point.intensity = 200; + } else { + point.intensity = 50; + } + // point.intensity = Cluster[Key].rkhs_decoding.associated_pattern_3d->col(i)(3); + OutPayload->push_back(point); + } + for (int i=0; ipush_back(point); + } + } + if (_mark_cluster_validity) { + + for (int i=0; ipush_back(point); + } + for (int i=0; ipush_back(point); + } + } + // Publish to a lidartag channel + _detectionArrayPublisher(Cluster[Key]); + + } + // if (PointsInClusters>_filling_max_points_threshold) { + // cout << "Too many points on a tag" << endl; + // // exit(-1); + // } + detectionsToPub.header = _point_cloud_header; + detectionsToPub.frame_index = _point_cloud_header.seq; + //cout << "BoundaryMarkerList size/10: " << BoundaryMarkerList.points.size()/10 << endl; + _boundary_marker_pub.publish(BoundMarkArray); + _cluster_marker_pub.publish(ClusterArray); + _payload_marker_pub.publish(PayloadMarkArray); + _id_marker_pub.publish(IDMarkArray); + // srand(time(0)); + // if (rand()%10 < 7) + _detectionArray_pub.publish(detectionsToPub); + } +} diff --git a/src/main.cc b/src/main.cc index c9dca5d..40d7419 100644 --- a/src/main.cc +++ b/src/main.cc @@ -29,7 +29,7 @@ */ #include -#include +#include using namespace std; diff --git a/src/utils.cc b/src/utils.cc index 90fb1f5..1c42510 100644 --- a/src/utils.cc +++ b/src/utils.cc @@ -32,540 +32,995 @@ #include "utils.h" #include #include +#include // std::iota +#include // std::sort, std::stable_sort namespace BipedLab{ - namespace utils { - // milisecond - double spendTime(const std::clock_t &t_end, const std::clock_t &t_start){ - return (((double) (t_end - t_start))/CLOCKS_PER_SEC)*1e3; - } - - std::string tranferToLowercase(std::string &t_data){ - std::transform(t_data.begin(), t_data.end(), t_data.begin(), ::tolower); - - return t_data; - } - - void pressEnterToContinue() { - int c; - printf("Press [Enter] key to continue.\n"); - while(getchar()!='\n'); // option TWO to clean stdin - getchar(); // wait for ENTER - } - - double deg2Rad(double t_degree){ - return t_degree*M_PI/180; - } - - double rad2Deg(double t_radian){ - return t_radian*180/M_PI; - } - - // Checks if a matrix is a valid rotation matrix. - bool isRotationMatrix(Eigen::Matrix3f &t_R) { - Eigen::Matrix3f should_be_identity = t_R*t_R.transpose(); - return (should_be_identity - Eigen::Matrix3f::Identity()).norm() < 1e-6; - } - - Eigen::Vector3f rotationMatrixToEulerAngles(Eigen::Matrix3f &t_R) { - // assert(isRotationMatrix(t_R)); - float sy = std::sqrt(t_R(0,0) * (0,0) + - t_R(1,0) * (1,0)); - - bool singular = sy < 1e-6; - - float x, y, z; - if (!singular) { - x = rad2Deg(std::atan(t_R(2,1)/ t_R(2,2))); - y = rad2Deg(std::atan(-t_R(2,0)/ sy)); - z = rad2Deg(std::atan(t_R(1,0)/ t_R(0,0))); - } - else { - x = rad2Deg(std::atan(-t_R(1,2)/ t_R(1,1))); - y = rad2Deg(std::atan(-t_R(2,0)/ sy)); - z = 0; - } - - return Eigen::Vector3f(x, y, z); - } - - - /* - * A function to check if get all parameters - */ - bool checkParameters(int t_n, ...){ - va_list vl_num; - va_start(vl_num, t_n); - bool Pass = true; - - for (int i=0; iindex < B->index; - } - - uint64_t bitShift(std::string const& t_value) { - uint64_t result = 0; - - char const* p = t_value.c_str(); - char const* q = p + t_value.size(); - while (p < q) { - result = (result << 1) + (result << 3) + *(p++) - '0'; - } - - return result; - } - - void normalize(std::vector &x, std::vector &y, - std::vector &z, std::vector &I, - const pcl::PointCloud t_payload){ - // normlize the y,z so the top left is (0,0) and bottom right is (1,1) - // as well as x axis - // o - // top left /| - // o----_o LiDAR ---> front o | back - // | | | o - // | | |/ - // o-----o o - // bottom right - float front_x = 1e8; - float back_x = -1e8; - float bottom_right_y = 1e8; - float top_left_y = -1e8; - float bottom_right_z = 1e8; - float top_left_z = -1e8; - - float max_intensity = -1e8; - - for (int i=0; ipoint.x>back_x) back_x = t_payload[i]->point.x; - if(t_payload[i]->point.xpoint.x; - - if(t_payload[i]->point.y>top_left_y) top_left_y = t_payload[i]->point.y; - if(t_payload[i]->point.ypoint.y; - - if(t_payload[i]->point.z>top_left_z) top_left_z = t_payload[i]->point.z; - if(t_payload[i]->point.zpoint.z; - if(t_payload[i]->point.intensity>max_intensity) max_intensity = t_payload[i]->point.intensity; - } - - float dx = std::abs(front_x - back_x); - float dy = std::abs(top_left_y - bottom_right_y); - float dz = std::abs(top_left_z - bottom_right_z); - for (int i=0; ipoint.x)/8; - y[i] = (top_left_y - t_payload[i]->point.y)/8; - z[i] = (top_left_z - t_payload[i]->point.z)/8; - I[i] = (t_payload[i]->point.intensity)/1.5; - } - } - - - void normalizeByAve(std::vector &x, std::vector &y, - std::vector &z, std::vector &I, - const pcl::PointCloud t_payload){ - float ave_x = 0; - float ave_y = 0; - float ave_z = 0; - - for (int i=0; ipoint.x; - ave_y += t_payload[i]->point.y; - ave_z += t_payload[i]->point.z; - x[i] = t_payload[i]->point.x; - y[i] = t_payload[i]->point.y; - z[i] = t_payload[i]->point.z; - I[i] = t_payload[i]->point.intensity; - } - ave_x /= t_payload.size(); - ave_y /= t_payload.size(); - ave_z /= t_payload.size(); - - for (int i=0; i duration = +// std::chrono::steady_clock::now() - clock_start; + +double spendElapsedTime( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start){ + std::chrono::duration duration = t_end - t_start; + return duration.count(); +} + +double spendElapsedTimeMilli( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start){ + return 1e3*spendElapsedTime(t_end, t_start); +} + +double spendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start){ + return 1.0/spendElapsedTime(t_end, t_start); +} + +double printSpendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start, + std::string txt){ + std::cout << std::fixed << std::setprecision(2) + << txt << spendElapsedHz(t_end, t_start) << " [Hz]" << std::endl; +} + +double printSpendElapsedHz( + const std::chrono::steady_clock::time_point &t_end, + const std::chrono::steady_clock::time_point &t_start){ + std::string text = "Elapsed time: "; + printSpendElapsedHz(t_end, t_start, text); +} + + + +// bool angleComparision (float i, float j) { +// return std::abs(i-j) < 1e-3; +// } + +std::string tranferToLowercase(std::string &t_data){ + std::transform(t_data.begin(), t_data.end(), t_data.begin(), ::tolower); + + return t_data; +} + + + +void pressEnterToContinue() { + int c; + printf("Press [Enter] key to continue.\n"); + while(getchar()!='\n'); // option TWO to clean stdin + getchar(); // wait for ENTER +} + + +// Checks if a matrix is a valid rotation matrix. +bool isRotationMatrix(Eigen::Matrix3f &t_R) { + Eigen::Matrix3f should_be_identity = t_R*t_R.transpose(); + return (should_be_identity - Eigen::Matrix3f::Identity()).norm() < 1e-6; +} + +Eigen::Vector3f rotationMatrixToEulerAngles(Eigen::Matrix3f &t_R) { + // assert(isRotationMatrix(t_R)); + float sy = std::sqrt(t_R(0,0) * (0,0) + + t_R(1,0) * (1,0)); + + bool singular = sy < 1e-6; + + float x, y, z; + if (!singular) { + x = rad2Deg(std::atan(t_R(2,1)/ t_R(2,2))); + y = rad2Deg(std::atan(-t_R(2,0)/ sy)); + z = rad2Deg(std::atan(t_R(1,0)/ t_R(0,0))); + } + else { + x = rad2Deg(std::atan(-t_R(1,2)/ t_R(1,1))); + y = rad2Deg(std::atan(-t_R(2,0)/ sy)); + z = 0; + } + + return Eigen::Vector3f(x, y, z); +} - float Norm (const velodyne_pointcloud::PointXYZIR& t_p){ - return std::sqrt(std::pow(t_p.y, 2) + std::pow(t_p.z, 2)); - } - - double MVN(const float &t_tag_size, const int &t_d, - const Eigen::Vector2f &t_X, const Eigen::Vector2f t_mean){ - Eigen::Matrix2f Sigma; - Sigma << t_tag_size/t_d/2, 0, 0, t_tag_size/t_d/2; - double sqrt2pi = std::sqrt(2 * M_PI); - double QuadForm = (t_X - t_mean).transpose() * Sigma.inverse() * (t_X - t_mean); - double Norm = std::pow(sqrt2pi, - 2) * - std::pow(Sigma.determinant(), - 0.5); - - return Norm * exp(-0.5 * QuadForm); - } - // step between p1 and p2 - float getStep(const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, const int t_d){ - return std::sqrt(std::pow((t_p2.y-t_p1.y), 2) + std::pow((t_p2.z-t_p1.z), 2))/t_d; - } - - // To get the t where p1 + t * v12 is the point that p projects onto line p12 - void getProjection(const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2, - const velodyne_pointcloud::PointXYZIR &t_p, - float &k, Eigen::Vector2f &t_v){ - // form vector from p1 to p2 and p1 to p - velodyne_pointcloud::PointXYZIR v12 = vectorize(t_p1, t_p2); - velodyne_pointcloud::PointXYZIR v1p = vectorize(t_p1, t_p); - - k = std::abs(dot(v12, v1p)/Norm(v12)); - // v = v12; - } - - void assignCellIndex(const float &t_tag_size, const Eigen::Matrix3f &t_R, - velodyne_pointcloud::PointXYZIR &t_p_reference, - const velodyne_pointcloud::PointXYZIR &t_average, - const int t_d, PayloadVoting_t &t_vote){ - // R: Payload p -> reference x - // prepare for Gaussian - float xOffset = t_vote.p->x - t_average.x; - float yOffset = t_vote.p->y - t_average.y; - float zOffset = t_vote.p->z - t_average.z; - // float x = t_vote.p->x; - // float y = t_vote.p->y; - // float z = t_vote.p->z; - - float x = xOffset*t_R(0,0) + yOffset*t_R(0,1) + zOffset*t_R(0,2); - float y = xOffset*t_R(1,0) + yOffset*t_R(1,1) + zOffset*t_R(1,2); - float z = xOffset*t_R(2,0) + yOffset*t_R(2,1) + zOffset*t_R(2,2); - - // x = x*t_R(0,0) + y*t_R(0,1) + z*t_R(0,2) + t_average.x; - // y = x*t_R(1,0) + y*t_R(1,1) + z*t_R(1,2) + t_average.y; - // z = x*t_R(2,0) + y*t_R(2,1) + z*t_R(2,2) + t_average.z; - // y,z should range int_ between -3s and 3s - t_p_reference.x = x; - t_p_reference.y = y; - t_p_reference.z = z; - float ss = t_tag_size/t_d; // scale back to the unit square - y = std::max(std::min(y, t_d/2*ss), (-t_d/2*ss+(float)0.001)); // don't match to 6 - z = std::max(std::min(z, t_d/2*ss), (-t_d/2*ss+(float)0.001)); // don't match to 6 - int cellIndexT = t_d/2 + std::floor(-y/ss); - int cellIndexK = t_d/2 + std::floor(-z/ss); - - float cy = (std::ceil(y/ss) - 0.5)*ss; // offset to center of each ceil - float cz = (std::ceil(z/ss) - 0.5)*ss; - - // which grid it belongs to (in 1-16 vector form)? - Eigen::Vector2f X(y, z); - Eigen::Vector2f Mean(cy, cz); - t_vote.centroid.x = 0; - t_vote.centroid.y = cy; - t_vote.centroid.z = cz; - t_vote.cell = t_d*cellIndexK + cellIndexT; - t_vote.weight = MVN(t_tag_size, t_d, X, Mean); - } - - // normalize weight and classify them into grid - void sortPointsToGrid(std::vector> &t_grid, - std::vector &t_votes){ - for (int i=0; i svd(M, Eigen::ComputeFullU | Eigen::ComputeFullV); - // Eigen::Matrix R = svd.matrixV()*svd.matrixU().transpose(); - Eigen::Matrix R = svd.matrixU()*svd.matrixV().transpose(); - H = R; // H: payload -> ref - } - - velodyne_pointcloud::PointXYZIR toVelodyne(const Eigen::Vector3f &t_p){ - velodyne_pointcloud::PointXYZIR point; - point.x = t_p[0]; - point.y = t_p[1]; - point.z = t_p[2]; - - return point; - } - - Eigen::Vector3f toEigen(const velodyne_pointcloud::PointXYZIR &t_point){ - Eigen::Vector3f tmp; - tmp[0] = t_point.x; - tmp[1] = t_point.y; - tmp[2] = t_point.z; - - return tmp; - } - - void minus(velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2){ - t_p1.x = t_p1.x - t_p2.x; - t_p1.y = t_p1.y - t_p2.y; - t_p1.z = t_p1.z - t_p2.z; - } - - float distance( - const velodyne_pointcloud::PointXYZIR &t_p1, - const velodyne_pointcloud::PointXYZIR &t_p2){ - return std::sqrt(std::pow((t_p1.x - t_p2.x), 2) + - std::pow((t_p1.y - t_p2.y), 2) + - std::pow((t_p1.z - t_p2.z), 2)); - } - - /* - * A function to calculate angle between va and vb - * return: angle in degree - */ - template - float getAngle (T a, U b) { - return rad2Deg(std::acos(dot(a, b)/ (Norm(a) * Norm(b)))); +/* + * A function to check if get all parameters + */ +bool checkParameters(int t_n, ...){ + va_list vl_num; + va_start(vl_num, t_n); + bool Pass = true; + + for (int i=0; i - (vectorize(t_p1, t_p2), vectorize(t_p1, t_p4)); - if ((Angle1 - (vectorize(t_p2, t_p1), vectorize(t_p2, t_p3)); - if ((Angle2 - (vectorize(t_p3, t_p2), vectorize(t_p3, t_p4)); - if ((Angle3 - (vectorize(t_p4, t_p3), vectorize(t_p4, t_p1)); - if ((Angle4index < B->index; +} + +uint64_t bitShift(std::string const& t_value) { + uint64_t result = 0; + + char const* p = t_value.c_str(); + char const* q = p + t_value.size(); + while (p < q) { + result = (result << 1) + (result << 3) + *(p++) - '0'; + } + + return result; +} + +void normalize(std::vector &x, std::vector &y, + std::vector &z, std::vector &I, + const pcl::PointCloud t_payload){ + // normlize the y,z so the top left is (0,0) and bottom right is (1,1) + // as well as x axis + // o + // top left /| + // o----_o LiDAR ---> front o | back + // | | | o + // | | |/ + // o-----o o + // bottom right + float front_x = 1e8; + float back_x = -1e8; + float bottom_right_y = 1e8; + float top_left_y = -1e8; + float bottom_right_z = 1e8; + float top_left_z = -1e8; + + float max_intensity = -1e8; + + for (int i=0; ipoint.x>back_x) + back_x = t_payload[i]->point.x; + if (t_payload[i]->point.xpoint.x; + + if (t_payload[i]->point.y>top_left_y) + top_left_y = t_payload[i]->point.y; + if (t_payload[i]->point.ypoint.y; + + if (t_payload[i]->point.z>top_left_z) + top_left_z = t_payload[i]->point.z; + if (t_payload[i]->point.zpoint.z; + if (t_payload[i]->point.intensity>max_intensity) + max_intensity = t_payload[i]->point.intensity; + } + + float dx = std::abs(front_x - back_x); + float dy = std::abs(top_left_y - bottom_right_y); + float dz = std::abs(top_left_z - bottom_right_z); + for (int i=0; ipoint.x)/8; + y[i] = (top_left_y - t_payload[i]->point.y)/8; + z[i] = (top_left_z - t_payload[i]->point.z)/8; + I[i] = (t_payload[i]->point.intensity)/1.5; + } +} + + +void normalizeByAve(std::vector &x, std::vector &y, + std::vector &z, std::vector &I, + const pcl::PointCloud t_payload){ + float ave_x = 0; + float ave_y = 0; + float ave_z = 0; + + for (int i=0; ipoint.x; + ave_y += t_payload[i]->point.y; + ave_z += t_payload[i]->point.z; + x[i] = t_payload[i]->point.x; + y[i] = t_payload[i]->point.y; + z[i] = t_payload[i]->point.z; + I[i] = t_payload[i]->point.intensity; + } + ave_x /= t_payload.size(); + ave_y /= t_payload.size(); + ave_z /= t_payload.size(); + + for (int i=0; i reference x + // prepare for Gaussian + float xOffset = t_vote.p->x - t_average.x; + float yOffset = t_vote.p->y - t_average.y; + float zOffset = t_vote.p->z - t_average.z; + // float x = t_vote.p->x; + // float y = t_vote.p->y; + // float z = t_vote.p->z; + + float x = xOffset*t_R(0,0) + yOffset*t_R(0,1) + zOffset*t_R(0,2); + float y = xOffset*t_R(1,0) + yOffset*t_R(1,1) + zOffset*t_R(1,2); + float z = xOffset*t_R(2,0) + yOffset*t_R(2,1) + zOffset*t_R(2,2); + + // x = x*t_R(0,0) + y*t_R(0,1) + z*t_R(0,2) + t_average.x; + // y = x*t_R(1,0) + y*t_R(1,1) + z*t_R(1,2) + t_average.y; + // z = x*t_R(2,0) + y*t_R(2,1) + z*t_R(2,2) + t_average.z; + // y,z should range int_ between -3s and 3s + t_p_reference.x = x; + t_p_reference.y = y; + t_p_reference.z = z; + float ss = t_tag_size/t_d; // scale back to the unit square + y = std::max(std::min(y, t_d/2*ss), (-t_d/2*ss+(float)0.001)); // don't match to 6 + z = std::max(std::min(z, t_d/2*ss), (-t_d/2*ss+(float)0.001)); // don't match to 6 + int cellIndexT = t_d/2 + std::floor(-y/ss); + int cellIndexK = t_d/2 + std::floor(-z/ss); + + float cy = (std::ceil(y/ss) - 0.5)*ss; // offset to center of each ceil + float cz = (std::ceil(z/ss) - 0.5)*ss; + + // which grid it belongs to (in 1-16 vector form)? + Eigen::Vector2f X(y, z); + Eigen::Vector2f Mean(cy, cz); + t_vote.centroid.x = 0; + t_vote.centroid.y = cy; + t_vote.centroid.z = cz; + t_vote.cell = t_d*cellIndexK + cellIndexT; + t_vote.weight = MVN(t_tag_size, t_d, X, Mean); +} + +// normalize weight and classify them into grid +void sortPointsToGrid(std::vector> &t_grid, + std::vector &t_votes){ + for (int i=0; i svd( + M, Eigen::ComputeFullU | Eigen::ComputeFullV); + // Eigen::Matrix R = svd.matrixV()*svd.matrixU().transpose(); + Eigen::Matrix R = + svd.matrixU()*svd.matrixV().transpose(); + H = R; // H: payload -> ref +} + +void fitGrid_new( + Eigen::MatrixXf &GridVertices, + Eigen::Matrix3f &H, + Eigen::MatrixXf &payload_vertices){ + + Eigen::Matrix3f M = + GridVertices.rightCols(4)*payload_vertices.transpose(); + Eigen::JacobiSVD svd( + M, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::Matrix R = + svd.matrixU()*svd.matrixV().transpose(); + H = R; // H: payload -> ref +} +velodyne_pointcloud::PointXYZIR toVelodyne(const Eigen::Vector3f &t_p){ + velodyne_pointcloud::PointXYZIR point; + point.x = t_p[0]; + point.y = t_p[1]; + point.z = t_p[2]; + + return point; +} + +Eigen::Vector3f toEigen(const velodyne_pointcloud::PointXYZIR &t_point){ + Eigen::Vector3f tmp; + tmp[0] = t_point.x; + tmp[1] = t_point.y; + tmp[2] = t_point.z; + + return tmp; +} + +void minus(velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2){ + t_p1.x = t_p1.x - t_p2.x; + t_p1.y = t_p1.y - t_p2.y; + t_p1.z = t_p1.z - t_p2.z; +} + +float distance( + const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2){ + return std::sqrt(std::pow((t_p1.x - t_p2.x), 2) + + std::pow((t_p1.y - t_p2.y), 2) + + std::pow((t_p1.z - t_p2.z), 2)); +} + +/* + * A function to calculate angle between va and vb + * return: angle in degree + */ +template + float getAngle (T a, U b) { + return rad2Deg(std::acos(dot(a, b)/ (Norm(a) * Norm(b)))); + } + +/* + * Check if 4 four corners are valid + * return 0: valid corners + * return -1: incorrect distance + * return -2: incorrect angle + */ +int checkCorners( + const float Tagsize, + const velodyne_pointcloud::PointXYZIR &t_p1, + const velodyne_pointcloud::PointXYZIR &t_p2, + const velodyne_pointcloud::PointXYZIR &t_p3, + const velodyne_pointcloud::PointXYZIR &t_p4){ + + // XXX tunable + float ratio = 1/3; + float AngleLowerBound = 75; + float AngleUpperBound = 105; + if (distance(t_p1, t_p2) < Tagsize*ratio) return -1; + if (distance(t_p1, t_p3) < Tagsize*ratio) return -1; + if (distance(t_p1, t_p4) < Tagsize*ratio) return -1; + if (distance(t_p2, t_p3) < Tagsize*ratio) return -1; + if (distance(t_p2, t_p4) < Tagsize*ratio) return -1; + if (distance(t_p3, t_p4) < Tagsize*ratio) return -1; + + // angle between p12 and p14 + float Angle1 = getAngle + (vectorize(t_p1, t_p2), vectorize(t_p1, t_p4)); + if ((Angle1 + (vectorize(t_p2, t_p1), vectorize(t_p2, t_p3)); + if ((Angle2 + (vectorize(t_p3, t_p2), vectorize(t_p3, t_p4)); + if ((Angle3 + (vectorize(t_p4, t_p3), vectorize(t_p4, t_p1)); + if ((Angle4 +T blockMatrix(int t_n, ...){ + va_list vl_num; + va_start(vl_num, t_n); + int cols_now = 0; + int rows_now = 0; + + for (int i=0; i - T blockMatrix(int t_n, ...){ - /* Function for creating blockdiagonal given arbitrary number of arguments. */ - va_list vl_num; - va_start(vl_num, t_n); - int cols_now = 0; - int rows_now = 0; - - for (int i=0; i - // Eigen::Matrix4d poseToEigenMatrix(const T &pose){ - Eigen::Matrix4d poseToEigenMatrix(const geometry_msgs::Pose &t_pose){ - Eigen::Matrix4d matrix_pose = Eigen::Matrix4d::Identity(); - matrix_pose(0, 3) = t_pose.position.x; - matrix_pose(1, 3) = t_pose.position.y; - matrix_pose(2, 3) = t_pose.position.z; - matrix_pose.topLeftCorner(3, 3) << qToR(t_pose); - - return matrix_pose; - } - - - // pose is geometry_msgs pose - template - Eigen::Matrix3d qToR(const T &t_pose){ - Eigen::Matrix3d R = Eigen::Matrix3d::Identity(); - double a = t_pose.orientation.w; - double b = t_pose.orientation.x; - double c = t_pose.orientation.y; - double d = t_pose.orientation.z; - R(0, 0) = std::pow(a, 2) + std::pow(b, 2) - std::pow(c, 2) - std::pow(d, 2); - R(0, 1) = 2*(b*c - a*d); - R(0, 2) = 2*(b*d + a*c); - - R(1, 0) = 2*(b*c + a*d); - R(1, 1) = std::pow(a, 2) - std::pow(b, 2) + std::pow(c, 2) - std::pow(d, 2); - R(1, 2) = 2*(c*d - a*b); - - R(2, 0) = 2*(b*d - a*c); - R(2, 1) = 2*(c*d + a*b); - R(2, 2) = std::pow(a, 2) - std::pow(b, 2) - std::pow(c, 2) + std::pow(d, 2); - - return R; + va_end(vl_num); + T Mblock = T::Zero(rows_now, cols_now); + va_list vl; + va_start(vl, t_n); + int rows = 0; + int cols = 0; + for (int i=0; i +// Eigen::Matrix4d poseToEigenMatrix(const T &pose){ +Eigen::Matrix4d poseToEigenMatrix(const geometry_msgs::Pose &t_pose){ + Eigen::Matrix4d matrix_pose = Eigen::Matrix4d::Identity(); + matrix_pose(0, 3) = t_pose.position.x; + matrix_pose(1, 3) = t_pose.position.y; + matrix_pose(2, 3) = t_pose.position.z; + matrix_pose.topLeftCorner(3, 3) << qToR(t_pose); + + return matrix_pose; +} + + +// pose is geometry_msgs pose +template + Eigen::Matrix3d qToR(const T &t_pose){ + Eigen::Matrix3d R = Eigen::Matrix3d::Identity(); + double a = t_pose.orientation.w; + double b = t_pose.orientation.x; + double c = t_pose.orientation.y; + double d = t_pose.orientation.z; + R(0, 0) = + std::pow(a, 2) + std::pow(b, 2) - std::pow(c, 2) - std::pow(d, 2); + R(0, 1) = 2*(b*c - a*d); + R(0, 2) = 2*(b*d + a*c); + + R(1, 0) = 2*(b*c + a*d); + R(1, 1) = + std::pow(a, 2) - std::pow(b, 2) + std::pow(c, 2) - std::pow(d, 2); + R(1, 2) = 2*(c*d - a*b); + + R(2, 0) = 2*(b*d - a*c); + R(2, 1) = 2*(c*d + a*b); + R(2, 2) = + std::pow(a, 2) - std::pow(b, 2) - std::pow(c, 2) + std::pow(d, 2); + + return R; + } + +Eigen::Matrix3d qToR(const Eigen::Vector3f &t_pose){ + Eigen::Matrix3d R = Eigen::Matrix3d::Identity(); + double a = 0; // w + double b = t_pose(0); // x + double c = t_pose(1); // y + double d = t_pose(2); // z + R(0, 0) = std::pow(a, 2) + std::pow(b, 2) - std::pow(c, 2) - std::pow(d, 2); + R(0, 1) = 2*(b*c - a*d); + R(0, 2) = 2*(b*d + a*c); + + R(1, 0) = 2*(b*c + a*d); + R(1, 1) = std::pow(a, 2) - std::pow(b, 2) + std::pow(c, 2) - std::pow(d, 2); + R(1, 2) = 2*(c*d - a*b); + + R(2, 0) = 2*(b*d - a*c); + R(2, 1) = 2*(c*d + a*b); + R(2, 2) = std::pow(a, 2) - std::pow(b, 2) - std::pow(c, 2) + std::pow(d, 2); + + return R; +} + + +Eigen::Matrix3d qMultiplication(const double &q1_w, const Eigen::Vector3f &q1, + const double &q2_w, const Eigen::Vector3f &q2){ +} + +/* + * Returns all numbers not in set, where the total set is [0,n) + */ +std::vector complementOfSet(const std::vector& set, std::size_t n) +{ + std::size_t curr_idx = 0; + std::vector complement; + + for (auto i = 0; i < n; i++) { + if (curr_idx >= set.size()) { complement.push_back(i); } + else if (i < set[curr_idx]) { complement.push_back(i); } + else if (i == set[curr_idx]) { curr_idx++; } // Inlier + } + + return complement; +} + +float dot_product(Eigen::Vector3f v1, Eigen::Vector3f v2){ + return v1[0]*v2[0] + v1[1]*v2[1] + v1[2]*v2[2]; +} + +Eigen::Vector3f cross_product(Eigen::Vector3f v1, Eigen::Vector3f v2){ + Eigen::Vector3f res; + res[0] = v1[1]*v2[2] - v1[2]*v2[1]; + res[1] = v1[2]*v2[0] - v1[0]*v2[2]; + res[2] = v1[0]*v2[1] - v1[1]*v2[0]; + return res; +} + + +void readDirectory(const std::string& name, std::vector &v){ + + boost::filesystem::path p(name); + boost::filesystem::directory_iterator start(p); + boost::filesystem::directory_iterator end; + std::transform(start, end, std::back_inserter(v), PathLeafString()); + std::sort(v.begin(), v.end()); +} + + +float computeMedian(const Eigen::VectorXf &eigen_vec){ + assert(eigen_vec.size()!=0); + std::vector vec( + eigen_vec.data(), eigen_vec.data() + eigen_vec.size()); + assert(vec.size()!=0); + if (vec.size() % 2 == 0) { + const auto median_it1 = vec.begin() + vec.size() / 2 - 1; + const auto median_it2 = vec.begin() + vec.size() / 2; + + std::nth_element(vec.begin(), median_it1 , vec.end()); + const auto e1 = *median_it1; + + std::nth_element(vec.begin(), median_it2 , vec.end()); + const auto e2 = *median_it2; + + return (e1 + e2) / 2; + + } else { + const auto median_it = vec.begin() + vec.size() / 2; + std::nth_element(vec.begin(), median_it , vec.end()); + + return *median_it; + } +} + +Eigen::MatrixXf +convertXYZIToHomogeneous(const Eigen::MatrixXf &mat_xyzi) { + assert(mat_xyzi.rows()==4 && + "The input dimension is wrong, it should be four"); + Eigen::MatrixXf mat_h = mat_xyzi; + mat_h.row(3).setOnes(); + + return mat_h; +} + +/* A function takes in rot_v as r, p, y in deg and trans_v as x, y, z in meter. + * It returns a rigid-body transformation. + * [Note] The rotation matrix from rpy follows the "XYZ" convention + */ +Eigen::Matrix4f +computeTransformation (Eigen::Vector3f rot_v, Eigen::Vector3f trans_v) { + Eigen::Matrix4f H = Eigen::Matrix4f::Identity(4, 4); + H.topLeftCorner(3, 3) = + computeRotX(rot_v(0)) * computeRotY(rot_v(1)) * computeRotZ(rot_v(2)); + H.topRightCorner(3, 1) = trans_v; + + return H; +} + +double get_sign(double x) { + double output; + if (x >= 0) { + output = 1; + } else { + output = -1; + } + return output; +} + +Eigen::Matrix3f +skew(const Eigen::Vector3d v) { + Eigen::Matrix3f m; + m << 0 , -v[2], v[1], + v[2], 0, -v[0], + -v[1], v[0], 0; + return m; +} + +Eigen::Vector3d +unskew(const Eigen::Matrix3f Ax) { + Eigen::Vector3d v(Ax(2,1), Ax(0,2), Ax(1,0)); + return v; +} + +Eigen::Matrix3f +Exp_SO3(const Eigen::Vector3d w) { + double theta = w.norm(); + Eigen::Matrix3f A = skew(w); + Eigen::Matrix3f output; + // cout << Eigen::Matrix3d::Identity() << endl; + if (theta == 0) { + output = Eigen::Matrix3f::Identity(); + } else { + output = Eigen::Matrix3f::Identity() + (std::sin(theta) / theta) * A + ((1 - std::cos(theta)) / std::pow(theta, 2)) * A * A; + } + return output; +} + +Eigen::Vector3d +Log_SO3(const Eigen::Matrix3f A) { + double theta = std::acos((A(0,0) + A(1,1) + A(2,2) - 1) / 2); + Eigen::Matrix3f A_transpose = A.transpose(); + Eigen::Vector3d output; + if (theta == 0) { + output = Eigen::Vector3d::Zero(3); + } else { + output = unskew(theta * (A - A_transpose) / (2 * std::sin(theta))); + } + return output; +} + + + +// 3D cross product of OA and OB vectors, +// (i.e x-component of their "2D" cross product, +// but remember that it is not defined in "2D"). +// Returns a positive value, if OAB makes a counter-clockwise turn, +// negative for clockwise turn, and zero if the points are collinear. +// compute on y-z plane and direction on x or -x axis +double cross( +const Eigen::Vector4f &O, const Eigen::Vector4f &A, const Eigen::Vector4f &B) { + return (A[1] - O[1]) * (B[2] - O[2]) - (A[2] - O[2]) * (B[1] - O[1]); +} + + +// comparator of transformed points, used for convex hull +void sortEigenVectorIndices(const Eigen::MatrixXf &mat, Eigen::VectorXi &indices) { + + // initialize original index locations + int num_elements = mat.cols(); + std::vector idx(num_elements); + std::iota(idx.begin(), idx.end(), 0); + + // sort indexes based on comparing values in v + // using std::stable_sort instead of std::sort + // to avoid unnecessary index re-orderings + // when v contains elements of equal values + std::stable_sort(idx.begin(), idx.end(), + [&mat](int i1, int i2) {return (mat(1, i1) < mat(1, i2)) || + (mat(1, i1) == mat(1, i2) && mat(2, i1) < mat(2, i2));}); + // Eigen::Transpositions indices(Eigen::Map>(idx)); + // Eigen::Transpositions indices; + // Eigen::Map test(idx.data()).cast(); + // printVector(idx); + int* ptr = &idx[0]; + Eigen::Map tmp(ptr, num_elements); + indices = tmp; +} + +// Vertices are in a 4xn matrix as [x,y,z,1] +// This function computes the area on y-z plane +float computePolygonArea(const Eigen::MatrixXf &vertices) { + // Initialze area + float area = 0.0; + + int num_pts = vertices.cols(); + + // Calculate value of shoelace formula + int j = num_pts - 1; + for (int i = 0; i < num_pts; i++) + { + area += (vertices(1, j) + vertices(1, i)) * + (vertices(2, j) - vertices(2, i)); + j = i; // j is previous vertex to i + } + + // Return absolute value + return abs(area / 2.0); +} + +// Returns a list of points on the convex hull in counter-clockwise order. +void constructConvexHull(const Eigen::MatrixXf &P, Eigen::MatrixXf &convex_hull) { + size_t n = P.cols(); + if (n <= 3) + convex_hull = P; + + // Eigen::MatrixXf Q(Eigen::MatrixXf::Random(3, 4)); + // Q(1, 0) = 3; + // Q(1, 1) = -1; + // Q(1, 2) = -2; + // Q(1, 3) = 5; + // Eigen::VectorXi indices; + // sortEigenVectorIndices(Q.row(1), indices); // sort by y + // Eigen::PermutationMatrix perm(indices); + // Eigen::MatrixXf sorted_points = Q * perm; + // std::cout << "Q: \n" << Q << std::endl; + // std::cout << "indices: \n" << indices << std::endl; + // std::cout << "sorted Q: \n" << sorted_points << std::endl; + + // Sort points lexicographically + Eigen::VectorXi indices; + sortEigenVectorIndices(P, indices); + Eigen::PermutationMatrix perm(indices); + Eigen::MatrixXf sorted_points = P * perm; + + // std::vector up; + // std::vector down; + // up.push_back(sorted_points.col(0)); + // down.push_back(sorted_points.col(0)); + // for (int i = 1; i < sorted_points.cols(); i++) { + // Eigen::Vector4d cur_pt = sorted_points.col(i); + // if (i == sorted_points.cols() - 1 || cross(left_most, cur_pt, right_most) > 0) { + // while (up.size() >= 2 && cross(up[up.size()-2], up[up.size()-1], cur_pt) <= 0) + // up.pop_back(); + // up.push_back(cur_pt); + // } + // if (i == sorted_points.cols() - 1 || cross(left_most, cur_pt, right_most) <=0) { + // while(down.size() >= 2 && cross(down[down.size()-2], down[down.size()-1], cur_pt) >= 0) + // down.pop_back(); + // down.push_back(cur_pt); + // } + // } + // up.insert(up.end(), down.begin(), down.end()-1); + // printVector(up); + + + Eigen::Vector4f left_most = sorted_points.col(0); + Eigen::Vector4f right_most = sorted_points.col(n - 1); + + Eigen::MatrixXf up = Eigen::MatrixXf::Zero(4, n); + Eigen::MatrixXf down = Eigen::MatrixXf::Zero(4, n); + up.col(0) = left_most; + // std::cout << "left p: \n" << left_most << std::endl; + // std::cout << "right p: \n" << right_most << std::endl; + // std::cout << "1. up: \n" << up << std::endl; + int k = 0; + int j = 0; + + for (int i = 0; i < sorted_points.cols(); i++) { + Eigen::Vector4f cur_pt = sorted_points.col(i); + if (i == sorted_points.cols() - 1 || cross(left_most, cur_pt, right_most) > 0) { + // std::cout << "i: " << i << std::endl; + while (k >= 2 && cross(up.col(k - 2), up.col(k - 1), cur_pt) <= 0) + k--; + up.col(k++) = cur_pt; + // std::cout << "k: " << k << std::endl; + // std::cout << "2. up: \n" << up << std::endl; } - - Eigen::Matrix3d qMultiplication(const double &q1_w, const Eigen::Vector3f &q1, - const double &q2_w, const Eigen::Vector3f &q2){ + if (i == sorted_points.cols() - 1 || cross(left_most, cur_pt, right_most) <=0) { + while(j >= 2 && cross(down.col(j - 2), down.col(j - 1), cur_pt) >= 0) + j--; + down.col(j++) = cur_pt; } - } // utils + } + convex_hull.resize(up.rows(), k + j -1); + convex_hull << up.leftCols(k), down.leftCols(j - 1).rowwise().reverse(); + // std::cout << "sorted P: \n" << sorted_points << std::endl; + // std::cout << "up: \n" << up << std::endl; + // std::cout << "down: \n" << down << std::endl; + // std::cout << "down reversed: \n" << down.leftCols(j - 1).rowwise().reverse() << std::endl; + // std::cout << "ch: \n" << convex_hull << std::endl; + // std::cout << "area: " << computePolygonArea(convex_hull) << std::endl; + // std::cout << "bool \n: " << up.cast() << std::endl; + // std::cout << "bool.col \n: " << up.cast().colwise() << std::endl; + // std::cout << "bool.col.all \n: " << up.cast().colwise().all() << std::endl; + // std::cout << "up: \n" << up << std::endl; + // std::cout << "bool: \n" << up.cast() << std::endl; + // std::cout << "test: \n" << up.cast().colwise().any() << std::endl; + // Eigen::MatrixXd res = up("", up.cast().colwise().any()); + // std::cout << "res: \n" << res << std::endl; + + // Eigen::MatrixXd convex_hull = Eigen::MatrixXd::Zero(4, 2 * n); + // // Build lower hull + // for (size_t i = 0; i < n; ++i) { + // while (k >= 2 && + // cross(convex_hull.col(k - 2), + // convex_hull.col(k - 1), + // sorted_points.col(i)) <= 0) { + // k--; + // } + // convex_hull.col(k++) = P.col(i); + // } + + // // Build upper hull + // for (size_t i = n - 1, t = k + 1; i > 0; --i) { + // while (k >= t && + // cross(convex_hull.col(k - 2), + // convex_hull.col(k - 1), + // sorted_points.col(i - 1)) <= 0) { + // k--; + // } + // convex_hull.col(k++) = P.col(i - 1); + // } + // std::cout << "convex_hull: \n" << convex_hull.leftCols(k - 1) << std::endl; + + // return convex_hull.leftCols(k - 1); +} + +// float computeMedian(std::vector &vec){ +// assert(vec.size()!=0); +// if (vec.size() % 2 == 0) { +// const auto median_it1 = vec.begin() + vec.size() / 2 - 1; +// const auto median_it2 = vec.begin() + vec.size() / 2; + +// std::nth_element(vec.begin(), median_it1 , vec.end()); +// const auto e1 = *median_it1; + +// std::nth_element(vec.begin(), median_it2 , vec.end()); +// const auto e2 = *median_it2; + +// return (e1 + e2) / 2; + +// } else { +// const auto median_it = vec.begin() + vec.size() / 2; +// std::nth_element(vec.begin(), median_it , vec.end()); + +// return *median_it; +// } +// } + + +// template +// T computeMedian(std::vector &vec){ +// assert(vec.size()!=0); +// if (vec.size() % 2 == 0) { +// const auto median_it1 = vec.begin() + vec.size() / 2 - 1; +// const auto median_it2 = vec.begin() + vec.size() / 2; + +// std::nth_element(vec.begin(), median_it1 , vec.end()); +// const T e1 = *median_it1; + +// std::nth_element(vec.begin(), median_it2 , vec.end()); +// const T e2 = *median_it2; + +// return (e1 + e2) / 2; + +// } else { +// const auto median_it = vec.begin() + vec.size() / 2; +// std::nth_element(vec.begin(), median_it , vec.end()); + +// return *median_it; +// } +// } + + +} // utils } // Bipedlab