├── .gitignore ├── CMakeLists.txt ├── README.MD ├── config ├── config_indoor.yaml └── config_outdoor.yaml ├── example └── place_recognition.cpp ├── figs ├── system_pipeline_btc.png └── video_cover.jpg ├── include ├── CustomMsg.h ├── CustomPoint.h ├── btc.h └── utils.h ├── launch └── place_recognition.launch ├── package.xml ├── poses ├── kitti00.txt ├── kitti02.txt ├── kitti05.txt ├── kitti06.txt ├── kitti07.txt └── kitti08.txt ├── rviz_cfg └── loop.rviz ├── src ├── btc.cpp └── utils.cpp └── supply └── Supplementary_Material_for_BTC.pdf /.gitignore: -------------------------------------------------------------------------------- 1 | # Edit at https://www.toptal.com/developers/gitignore?templates=python 2 | 3 | ### Python ### 4 | # Byte-compiled / optimized / DLL files 5 | __pycache__/ 6 | *.py[cod] 7 | *$py.class 8 | 9 | # C extensions 10 | *.so 11 | 12 | # Distribution / packaging 13 | .Python 14 | build/ 15 | develop-eggs/ 16 | dist/ 17 | downloads/ 18 | eggs/ 19 | .eggs/ 20 | lib/ 21 | lib64/ 22 | parts/ 23 | sdist/ 24 | var/ 25 | wheels/ 26 | share/python-wheels/ 27 | *.egg-info/ 28 | .installed.cfg 29 | *.egg 30 | MANIFEST 31 | 32 | # PyInstaller 33 | # Usually these files are written by a python script from a template 34 | # before PyInstaller builds the exe, so as to inject date/other infos into it. 35 | *.manifest 36 | *.spec 37 | 38 | # Installer logs 39 | pip-log.txt 40 | pip-delete-this-directory.txt 41 | 42 | # Unit test / coverage reports 43 | htmlcov/ 44 | .tox/ 45 | .nox/ 46 | .coverage 47 | .coverage.* 48 | .cache 49 | nosetests.xml 50 | coverage.xml 51 | *.cover 52 | *.py,cover 53 | .hypothesis/ 54 | .pytest_cache/ 55 | cover/ 56 | 57 | # Translations 58 | *.mo 59 | *.pot 60 | 61 | # Django stuff: 62 | *.log 63 | local_settings.py 64 | db.sqlite3 65 | db.sqlite3-journal 66 | 67 | # Flask stuff: 68 | instance/ 69 | .webassets-cache 70 | 71 | # Scrapy stuff: 72 | .scrapy 73 | 74 | # Sphinx documentation 75 | docs/_build/ 76 | 77 | # PyBuilder 78 | .pybuilder/ 79 | target/ 80 | 81 | # Jupyter Notebook 82 | .ipynb_checkpoints 83 | 84 | # IPython 85 | profile_default/ 86 | ipython_config.py 87 | 88 | # pyenv 89 | # For a library or package, you might want to ignore these files since the code is 90 | # intended to run in multiple environments; otherwise, check them in: 91 | # .python-version 92 | 93 | # pipenv 94 | # According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. 95 | # However, in case of collaboration, if having platform-specific dependencies or dependencies 96 | # having no cross-platform support, pipenv may install dependencies that don't work, or not 97 | # install all needed dependencies. 98 | #Pipfile.lock 99 | 100 | # poetry 101 | # Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. 102 | # This is especially recommended for binary packages to ensure reproducibility, and is more 103 | # commonly ignored for libraries. 104 | # https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control 105 | #poetry.lock 106 | 107 | # pdm 108 | # Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. 109 | #pdm.lock 110 | # pdm stores project-wide configurations in .pdm.toml, but it is recommended to not include it 111 | # in version control. 112 | # https://pdm.fming.dev/#use-with-ide 113 | .pdm.toml 114 | 115 | # PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm 116 | __pypackages__/ 117 | _skbuild/ 118 | 119 | # Celery stuff 120 | celerybeat-schedule 121 | celerybeat.pid 122 | 123 | # SageMath parsed files 124 | *.sage.py 125 | 126 | # Environments 127 | .env 128 | .venv 129 | env/ 130 | venv/ 131 | ENV/ 132 | env.bak/ 133 | venv.bak/ 134 | 135 | # Spyder project settings 136 | .spyderproject 137 | .spyproject 138 | 139 | # Rope project settings 140 | .ropeproject 141 | 142 | # mkdocs documentation 143 | /site 144 | 145 | # mypy 146 | .mypy_cache/ 147 | .dmypy.json 148 | dmypy.json 149 | 150 | # Pyre type checker 151 | .pyre/ 152 | 153 | # pytype static type analyzer 154 | .pytype/ 155 | 156 | # Cython debug symbols 157 | cython_debug/ 158 | 159 | # PyCharm 160 | # JetBrains specific template is maintained in a separate JetBrains.gitignore that can 161 | # be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore 162 | # and can be added to the global gitignore or merged into this file. For a more nuclear 163 | # option (not recommended) you can uncomment the following to ignore the entire idea folder. 164 | #.idea/ 165 | 166 | ### Python Patch ### 167 | # Poetry local configuration file - https://python-poetry.org/docs/configuration/#local-configuration 168 | poetry.toml 169 | 170 | # ruff 171 | .ruff_cache/ 172 | 173 | # LSP config files 174 | pyrightconfig.json 175 | 176 | # End of https://www.toptal.com/developers/gitignore/api/python 177 | # Created by https://www.toptal.com/developers/gitignore/api/cmake 178 | # Edit at https://www.toptal.com/developers/gitignore?templates=cmake 179 | 180 | ### CMake ### 181 | CMakeLists.txt.user 182 | CMakeCache.txt 183 | CMakeFiles 184 | CMakeScripts 185 | Testing 186 | Makefile 187 | cmake_install.cmake 188 | install_manifest.txt 189 | compile_commands.json 190 | CTestTestfile.cmake 191 | _deps 192 | 193 | ### CMake Patch ### 194 | # External projects 195 | *-prefix/ 196 | 197 | # End of https://www.toptal.com/developers/gitignore/api/cmake 198 | n# Created by https://www.toptal.com/developers/gitignore/api/c++ 199 | # Edit at https://www.toptal.com/developers/gitignore?templates=c++ 200 | 201 | ### C++ ### 202 | # Prerequisites 203 | *.d 204 | 205 | # Compiled Object files 206 | *.slo 207 | *.lo 208 | *.o 209 | *.obj 210 | 211 | # Precompiled Headers 212 | *.gch 213 | *.pch 214 | 215 | # Compiled Dynamic libraries 216 | *.so 217 | *.dylib 218 | *.dll 219 | 220 | # Fortran module files 221 | *.mod 222 | *.smod 223 | 224 | # Compiled Static libraries 225 | *.lai 226 | *.la 227 | *.a 228 | *.lib 229 | 230 | # Executables 231 | *.exe 232 | *.out 233 | *.app 234 | 235 | # End of https://www.toptal.com/developers/gitignore/api/c++ 236 | 237 | .vscode/# Created by https://www.toptal.com/developers/gitignore/api/ros 238 | # Edit at https://www.toptal.com/developers/gitignore?templates=ros 239 | 240 | ### ROS ### 241 | devel/ 242 | logs/ 243 | build/ 244 | bin/ 245 | lib/ 246 | msg_gen/ 247 | srv_gen/ 248 | msg/*Action.msg 249 | msg/*ActionFeedback.msg 250 | msg/*ActionGoal.msg 251 | msg/*ActionResult.msg 252 | msg/*Feedback.msg 253 | msg/*Goal.msg 254 | msg/*Result.msg 255 | msg/_*.py 256 | build_isolated/ 257 | devel_isolated/ 258 | 259 | # Generated by dynamic reconfigure 260 | *.cfgc 261 | /cfg/cpp/ 262 | /cfg/*.py 263 | 264 | # Ignore generated docs 265 | *.dox 266 | *.wikidoc 267 | 268 | # eclipse stuff 269 | .project 270 | .cproject 271 | 272 | # qcreator stuff 273 | CMakeLists.txt.user 274 | 275 | srv/_*.py 276 | *.pcd 277 | *.pyc 278 | qtcreator-* 279 | *.user 280 | 281 | /planning/cfg 282 | /planning/docs 283 | /planning/src 284 | 285 | *~ 286 | 287 | # Emacs 288 | .#* 289 | 290 | # Catkin custom files 291 | CATKIN_IGNORE 292 | 293 | # End of https://www.toptal.com/developers/gitignore/api/ros 294 | n -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(btc_desc) 3 | 4 | ## Compile as C++11, supported in ROS Kinetic and newer 5 | set(CMAKE_EXPORT_COMPILE_COMMANDS ON) 6 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 7 | set(CMAKE_CXX_EXTENSIONS OFF) 8 | set(CMAKE_CXX_STANDARD 17) 9 | SET(CMAKE_BUILD_TYPE "Release") 10 | #SET(CMAKE_CXX_FLAGS_DEBUG "$ENV{CXXFLAGS} -O0 -Wall -g -ggdb") 11 | #SET(CMAKE_CXX_FLAGS_RELEASE "$ENV{CXXFLAGS} -O3 -Wall") 12 | ## Find catkin macros and libraries 13 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 14 | ## is used, also find other catkin packages 15 | find_package(catkin REQUIRED COMPONENTS 16 | cv_bridge 17 | pcl_conversions 18 | pcl_ros 19 | roscpp 20 | rospy 21 | sensor_msgs 22 | std_msgs 23 | tf_conversions 24 | ) 25 | 26 | ## System dependencies are found with CMake's conventions 27 | # find_package(Boost REQUIRED COMPONENTS system) 28 | find_package(PCL REQUIRED) 29 | find_package(OpenCV REQUIRED) 30 | find_package(Threads) 31 | find_package(Ceres REQUIRED) 32 | find_package(GTSAM REQUIRED QUIET) 33 | 34 | set(CMAKE_AUTOMOC ON) 35 | set(CMAKE_AUTOUIC ON) 36 | set(CMAKE_AUTORCC ON) 37 | set(CMAKE_INCLUDE_CURRENT_DIR ON) 38 | 39 | catkin_package( 40 | CATKIN_DEPENDS roscpp rospy std_msgs 41 | ) 42 | 43 | include_directories( 44 | # include 45 | ${catkin_INCLUDE_DIRS} 46 | ${PCL_INCLUDE_DIRS} 47 | ${OpenCV_INCLUDE_DIRS} 48 | ) 49 | 50 | add_library(utils_lib src/utils.cpp) 51 | 52 | 53 | add_executable(btc_place_recognition example/place_recognition.cpp src/btc.cpp) 54 | target_link_libraries(btc_place_recognition 55 | ${catkin_LIBRARIES} 56 | ${PCL_LIBRARIES} 57 | ${OpenCV_LIBS} 58 | ${CERES_LIBRARIES} 59 | tbb 60 | utils_lib) 61 | 62 | 63 | -------------------------------------------------------------------------------- /README.MD: -------------------------------------------------------------------------------- 1 | # BTC 2 | ## BTC: A Binary and Triangle Combined Descriptor for 3D Place Recognition 3 | 4 | ## Introduction 5 | **BTC** is a novel global and local combined descriptor for 3D place recognition. To achieve viewpoint invariance, we devise a global triangle descriptor composed of three side lengths of a triangle formed by three keypoints extracted from the accumulated point cloud. The triangle descriptor inherently exhibits viewpoint invariance, as the side lengths remain unchanged regardless of viewpoint or direction. While the triangle descriptor captures the global appearance of the point cloud, to further enhance its descriptive and discriminative capabilities, we develop a local descriptor called the binary descriptor that encodes the local geometric information of each keypoint forming the triangle. This combination of global and local descriptors allows for accurate and robust place recognition, even in large-scale unstructured environments. 6 | 7 |
8 | 9 | System overview of the Binary Triangle Combined (BTC) descriptor for place recognition in a SLAM system. 10 |
11 | 12 | ### Developers: 13 | [Chongjian Yuan 袁崇健](https://github.com/ChongjianYUAN), [Jiarong Lin 林家荣](https://github.com/ziv-lin) 14 | 15 | ### Related Paper 16 | The related paper will be available on **arxiv** soon. 17 | 18 | ### Related Video 19 | Our accompanying video is now available on **YouTube**. 20 |
21 | 22 |
23 | 24 | ## Parameters Explanation 25 | 26 | ### Binary Descriptor Parameters 27 | - `useful_corner_num`: Maximum number of useful corners. 28 | - `plane_detection_thre`: Threshold for plane detection. 29 | - `plane_merge_normal_thre`: Normal threshold for plane merging. 30 | - `plane_merge_dis_thre`: Distance threshold for plane merging. 31 | - `voxel_size`: Size of each voxel. 32 | - `voxel_init_num`: Minimum number of points in a voxel for extraction. 33 | - `proj_plane_num`: Number of projection planes. 34 | - `proj_image_resolution`: Resolution of the projected image in meters. 35 | - `proj_image_high_inc`: Height increment for the projected image in meters. 36 | - `proj_dis_min`: Minimum distance to the projection plane. 37 | - `proj_dis_max`: Maximum distance to the projection plane. 38 | - `summary_min_thre`: Minimum number of points in one image grid. 39 | - `line_filter_enable`: Enable line point filtering; turn off in environments lacking features (indoor and outdoor), otherwise enable to reduce computation 40 | 41 | ### Stable Triangle Descriptor Parameters 42 | - `descriptor_near_num`: Number of neighboring points to save for each point when generating triangles. 43 | - `descriptor_min_len`: Minimum edge length. 44 | - `descriptor_max_len`: Maximum edge length. 45 | - `max_constrait_dis`: Neighborhood range for non-maximum suppression. 46 | - `triangle_resolution`: Edge length amplification coefficient. 47 | 48 | ### Candidate Search Parameters 49 | - `skip_near_num`: Number of frames to skip. 50 | - `candidate_num`: Maximum number of reference frames. 51 | - `similarity_threshold`: BTC similarity coefficient. 52 | - `rough_dis_threshold`: Threshold coefficient for BTC edge length distance. 53 | - `normal_threshold`: Normal Threshold for plane-to-plane validation. 54 | - `dis_threshold`: Distance threshold for plane-to-plane validation. 55 | - `icp_threshold`: Threshold for plane-to-plane ICP to triggle loop. 56 | 57 | ## Example 58 | 59 | ### Place Recognition 60 | To perform place recognition using the BTC descriptor, you need to prepare the data and then launch the ROS node with the following command: 61 | 62 | 1. **Data Preparation**: 63 | - Prepare the submap LiDAR point cloud directories containing the point cloud files in either `.bin` or `.pcd` format. 64 | - File naming format should follow this convention: 65 | - For PCD files: `000000.pcd`, `000001.pcd`, ..., up to your maximum submap count. 66 | - For BIN files: similarly named as `000000.bin`, `000001.bin`, etc. 67 | - Prepare a `pose.txt` file with the following format: 68 | ``` 69 | Submap_id pos_x pos_y pos_z quat_x quat_y quat_z quat_w 70 | ``` 71 | where: 72 | - `Submap_id` is the identifier for the submap. 73 | - `pos_x`, `pos_y`, `pos_z` are the coordinates of the submap's position. 74 | - `quat_x`, `quat_y`, `quat_z`, `quat_w` are the quaternion components representing the orientation. 75 | 76 | 2. **Launch the Node**: 77 | Run the following command to start the place recognition process: 78 | 79 | ```bash 80 | roslaunch btc_desc place_recognition.launch 81 | ``` 82 | 83 | ### More Examples 84 | More examples to be released soon: 85 | - **Multi-Session Place Recognition** 86 | - **Global Relocalization** 87 | - **Pose Graph Optimization (PGO)** 88 | - **Multi-Map Merge** 89 | -------------------------------------------------------------------------------- /config/config_indoor.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | 3 | # binary descriptor 4 | useful_corner_num: 500 # Maximum number of triangle vertices 5 | plane_detection_thre: 0.01 # Maximum allowed value for the minimum eigenvalue of the covariance matrix to consider as a plane 6 | plane_merge_normal_thre: 0.1 # Normal threshold for plane merging 7 | plane_merge_dis_thre: 0.3 # Distance threshold for plane merging 8 | voxel_size: 0.5 # Side length of each voxel during plane extraction 9 | voxel_init_num: 10 # Minimum number of points in the voxel for plane extraction 10 | proj_plane_num: 2 # Number of projection planes 11 | proj_image_resolution: 0.2 # In meters 12 | proj_image_high_inc: 0.1 # In meters 13 | proj_dis_min: -1.0 # Minimum distance to the projection plane 14 | proj_dis_max: 4.0 # Maximum distance to the projection plane 15 | summary_min_thre: 6 # Minimum number of points in one image grid 16 | line_filter_enable: 0 # Enable line point filtering; turn off in environments lacking features (indoor and outdoor), otherwise enable to reduce computation 17 | 18 | # std descriptor 19 | descriptor_near_num: 15 # Number of neighboring points to save for each point when generating triangles 20 | descriptor_min_len: 1 # Minimum edge length 21 | descriptor_max_len: 30 # Maximum edge length 22 | max_constrait_dis: 1 # Neighborhood range for non-maximum suppression 23 | triangle_resolution: 0.2 # Edge length amplification coefficient 24 | 25 | # candidate search 26 | skip_near_num: 100 # Number of frames to skip; set to a positive value for intra-machine loops, and -1000000 for inter-machine loops 27 | candidate_num: 50 # Maximum number of reference frames 28 | similarity_threshold: 0.7 # BTC similarity coefficient 29 | rough_dis_threshold: 0.01 # Threshold coefficient for BTC edge length distance 30 | normal_threshold: 0.2 # Threshold for plane ICP and geometric validation: point-to-plane distance 31 | dis_threshold: 0.5 # Distance threshold for point-to-plane validation 32 | icp_threshold: 0.2 # Threshold for plane-to-plane ICP to triggle loop. 33 | -------------------------------------------------------------------------------- /config/config_outdoor.yaml: -------------------------------------------------------------------------------- 1 | %YAML:1.0 2 | 3 | # binary descriptor 4 | useful_corner_num: 500 # Maximum number of useful corners 5 | plane_detection_thre: 0.01 # Threshold for plane detection 6 | plane_merge_normal_thre: 0.1 # Normal threshold for plane merging 7 | plane_merge_dis_thre: 0.3 # Distance threshold for plane merging 8 | voxel_size: 2 # Size of each voxel 9 | voxel_init_num: 10 # Minimum number of points in a voxel for extraction 10 | proj_plane_num: 1 # Number of projection planes 11 | proj_image_resolution: 0.5 # Resolution of the projected image in meters 12 | proj_image_high_inc: 0.1 # Height increment for the projected image in meters 13 | proj_dis_min: -1.0 # Minimum distance to the projection plane 14 | proj_dis_max: 4.0 # Maximum distance to the projection plane 15 | summary_min_thre: 10 # Minimum number of points in one image grid 16 | line_filter_enable: 1 # Enable line point filtering (1: enabled, 0: disabled) 17 | 18 | # std descriptor 19 | descriptor_near_num: 10 # Number of neighboring points to save for each point when generating triangles 20 | descriptor_min_len: 2 # Minimum edge length 21 | descriptor_max_len: 50 # Maximum edge length 22 | max_constrait_dis: 2 # Neighborhood range for non-maximum suppression 23 | triangle_resolution: 0.2 # Edge length amplification coefficient 24 | 25 | # candidate search 26 | skip_near_num: 100 # Number of frames to skip 27 | candidate_num: 50 # Maximum number of reference frames 28 | similarity_threshold: 0.7 # BTC similarity coefficient 29 | rough_dis_threshold: 0.01 # Threshold coefficient for BTC edge length distance 30 | normal_threshold: 0.2 # Threshold for plane ICP and geometric validation: point-to-plane distance 31 | dis_threshold: 0.5 # Distance threshold for plane-to-plane validation. 32 | icp_threshold: 0.2 # Threshold for plane-to-plane ICP to triggle loop. 33 | -------------------------------------------------------------------------------- /example/place_recognition.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | #include "include/btc.h" 10 | #include "include/utils.h" 11 | 12 | // Read KITTI data 13 | std::vector read_lidar_data(const std::string lidar_data_path) { 14 | std::ifstream lidar_data_file; 15 | lidar_data_file.open(lidar_data_path, 16 | std::ifstream::in | std::ifstream::binary); 17 | if (!lidar_data_file) { 18 | std::cout << "Read End..." << std::endl; 19 | std::vector nan_data; 20 | return nan_data; 21 | // exit(-1); 22 | } 23 | lidar_data_file.seekg(0, std::ios::end); 24 | const size_t num_elements = lidar_data_file.tellg() / sizeof(float); 25 | lidar_data_file.seekg(0, std::ios::beg); 26 | 27 | std::vector lidar_data_buffer(num_elements); 28 | lidar_data_file.read(reinterpret_cast(&lidar_data_buffer[0]), 29 | num_elements * sizeof(float)); 30 | return lidar_data_buffer; 31 | } 32 | 33 | int main(int argc, char **argv) { 34 | ros::init(argc, argv, "btc_place_recognition"); 35 | ros::NodeHandle nh; 36 | std::string setting_path = ""; 37 | std::string pcds_dir = ""; 38 | std::string pose_file = ""; 39 | std::string result_file = ""; 40 | double cloud_overlap_thr = 0.5; 41 | bool calc_gt_enable = false; 42 | bool read_bin = true; 43 | nh.param("cloud_overlap_thr", cloud_overlap_thr, 0.5); 44 | nh.param("setting_path", setting_path, ""); 45 | nh.param("pcds_dir", pcds_dir, ""); 46 | nh.param("pose_file", pose_file, ""); 47 | nh.param("read_bin", read_bin, true); 48 | 49 | ros::Publisher pubOdomAftMapped = 50 | nh.advertise("/aft_mapped_to_init", 10); 51 | ros::Publisher pubCureentCloud = 52 | nh.advertise("/cloud_current", 100); 53 | ros::Publisher pubCurrentBinary = 54 | nh.advertise("/cloud_key_points", 100); 55 | ros::Publisher pubPath = 56 | nh.advertise("descriptor_line", 10); 57 | ros::Publisher pubCurrentPose = 58 | nh.advertise("/current_pose", 10); 59 | ros::Publisher pubMatchedPose = 60 | nh.advertise("/matched_pose", 10); 61 | ros::Publisher pubMatchedCloud = 62 | nh.advertise("/cloud_matched", 100); 63 | ros::Publisher pubMatchedBinary = 64 | nh.advertise("/cloud_matched_key_points", 100); 65 | ros::Publisher pubLoopStatus = 66 | nh.advertise("/loop_status", 100); 67 | ros::Publisher pubBTC = 68 | nh.advertise("descriptor_line", 10); 69 | 70 | std_msgs::ColorRGBA color_tp; 71 | std_msgs::ColorRGBA color_fp; 72 | std_msgs::ColorRGBA color_path; 73 | double scale_tp = 4.0; 74 | double scale_fp = 5.0; 75 | double scale_path = 3.0; 76 | color_tp.a = 1.0; 77 | color_tp.r = 0.0 / 255.0; 78 | color_tp.g = 255.0 / 255.0; 79 | color_tp.b = 0.0 / 255.0; 80 | 81 | color_fp.a = 1.0; 82 | color_fp.r = 1.0; 83 | color_fp.g = 0.0; 84 | color_fp.b = 0.0; 85 | 86 | color_path.a = 0.8; 87 | color_path.r = 255.0 / 255.0; 88 | color_path.g = 255.0 / 255.0; 89 | color_path.b = 255.0 / 255.0; 90 | 91 | ros::Rate loop(50000); 92 | ros::Rate slow_loop(1000); 93 | 94 | ConfigSetting config_setting; 95 | load_config_setting(setting_path, config_setting); 96 | 97 | // pose is only for visulization and gt overlap calculation 98 | std::vector> pose_list; 99 | std::vector time_list; 100 | load_evo_pose_with_time(pose_file, pose_list, time_list); 101 | std::string print_msg = "Successfully load pose file:" + pose_file + 102 | ". pose size:" + std::to_string(time_list.size()); 103 | ROS_INFO_STREAM(print_msg.c_str()); 104 | 105 | BtcDescManager *btc_manager = new BtcDescManager(config_setting); 106 | btc_manager->print_debug_info_ = false; 107 | pcl::PointCloud::Ptr temp_cloud( 108 | new pcl::PointCloud()); 109 | 110 | std::vector descriptor_time; 111 | std::vector querying_time; 112 | std::vector update_time; 113 | int triggle_loop_num = 0; 114 | int true_loop_num = 0; 115 | bool finish = false; 116 | 117 | pcl::PCDReader reader; 118 | 119 | while (ros::ok() && !finish) { 120 | for (size_t submap_id = 0; submap_id < pose_list.size(); ++submap_id) { 121 | pcl::PointCloud::Ptr cloud( 122 | new pcl::PointCloud()); 123 | pcl::PointCloud transform_cloud; 124 | cloud->reserve(1000000); 125 | transform_cloud.reserve(1000000); 126 | // Get pose information, only for gt overlap calculation 127 | Eigen::Vector3d translation = pose_list[submap_id].first; 128 | Eigen::Matrix3d rotation = pose_list[submap_id].second; 129 | if (read_bin) { 130 | std::stringstream ss; 131 | ss << pcds_dir << "/" << std::setfill('0') << std::setw(6) << submap_id 132 | << ".bin"; 133 | std::string pcd_file = ss.str(); 134 | auto t_load_start = std::chrono::high_resolution_clock::now(); 135 | std::vector lidar_data = read_lidar_data(ss.str()); 136 | if (lidar_data.size() == 0) { 137 | break; 138 | } 139 | 140 | for (std::size_t i = 0; i < lidar_data.size(); i += 4) { 141 | pcl::PointXYZI point; 142 | point.x = lidar_data[i]; 143 | point.y = lidar_data[i + 1]; 144 | point.z = lidar_data[i + 2]; 145 | point.intensity = lidar_data[i + 3]; 146 | Eigen::Vector3d pv = point2vec(point); 147 | pv = rotation * pv + translation; 148 | cloud->points.push_back(point); 149 | point = vec2point(pv); 150 | transform_cloud.points.push_back(vec2point(pv)); 151 | } 152 | auto t_load_end = std::chrono::high_resolution_clock::now(); 153 | std::cout << "[Time] load cloud: " << time_inc(t_load_end, t_load_start) 154 | << "ms, " << std::endl; 155 | } else { 156 | // Load point cloud from pcd file 157 | std::stringstream ss; 158 | ss << pcds_dir << "/" << std::setfill('0') << std::setw(6) << submap_id 159 | << ".pcd"; 160 | std::string pcd_file = ss.str(); 161 | 162 | auto t_load_start = std::chrono::high_resolution_clock::now(); 163 | // pcl::io::loadPCDFile(pcd_file, *cloud) 164 | if (reader.read(pcd_file, *cloud) == -1) { 165 | ROS_ERROR_STREAM("Couldn't read file " << pcd_file); 166 | continue; 167 | } 168 | auto t_load_end = std::chrono::high_resolution_clock::now(); 169 | std::cout << "[Time] load cloud: " << time_inc(t_load_end, t_load_start) 170 | << "ms, " << std::endl; 171 | transform_cloud = *cloud; 172 | 173 | for (size_t j = 0; j < transform_cloud.size(); j++) { 174 | Eigen::Vector3d pv = point2vec(transform_cloud.points[j]); 175 | pv = rotation * pv + translation; 176 | transform_cloud.points[j] = vec2point(pv); 177 | } 178 | } 179 | 180 | // step1. Descriptor Extraction 181 | std::cout << "[Description] submap id:" << submap_id << std::endl; 182 | auto t_descriptor_begin = std::chrono::high_resolution_clock::now(); 183 | std::vector btcs_vec; 184 | btc_manager->GenerateBtcDescs(transform_cloud.makeShared(), submap_id, 185 | btcs_vec); 186 | auto t_descriptor_end = std::chrono::high_resolution_clock::now(); 187 | descriptor_time.push_back(time_inc(t_descriptor_end, t_descriptor_begin)); 188 | // step2. Searching Loop 189 | auto t_query_begin = std::chrono::high_resolution_clock::now(); 190 | std::pair search_result(-1, 0); 191 | std::pair loop_transform; 192 | loop_transform.first << 0, 0, 0; 193 | loop_transform.second = Eigen::Matrix3d::Identity(); 194 | std::vector> loop_std_pair; 195 | if (submap_id > config_setting.skip_near_num_) { 196 | if (btcs_vec.size() == 0) { 197 | // getchar(); 198 | } 199 | btc_manager->SearchLoop(btcs_vec, search_result, loop_transform, 200 | loop_std_pair); 201 | } 202 | if (search_result.first > 0) { 203 | std::cout << "[Loop Detection] triggle loop: " << submap_id << "--" 204 | << search_result.first << ", score:" << search_result.second 205 | << std::endl; 206 | } 207 | auto t_query_end = std::chrono::high_resolution_clock::now(); 208 | querying_time.push_back(time_inc(t_query_end, t_query_begin)); 209 | 210 | // step3. Add descriptors to the database 211 | auto t_map_update_begin = std::chrono::high_resolution_clock::now(); 212 | btc_manager->AddBtcDescs(btcs_vec); 213 | auto t_map_update_end = std::chrono::high_resolution_clock::now(); 214 | update_time.push_back(time_inc(t_map_update_end, t_map_update_begin)); 215 | std::cout << "[Time] descriptor extraction: " 216 | << time_inc(t_descriptor_end, t_descriptor_begin) << "ms, " 217 | << "query: " << time_inc(t_query_end, t_query_begin) << "ms, " 218 | << "update map:" 219 | << time_inc(t_map_update_end, t_map_update_begin) << "ms" 220 | << std::endl; 221 | std::cout << std::endl; 222 | 223 | // down sample to save memory 224 | down_sampling_voxel(transform_cloud, 0.5); 225 | btc_manager->key_cloud_vec_.push_back(transform_cloud.makeShared()); 226 | 227 | // visuliazaion 228 | sensor_msgs::PointCloud2 pub_cloud; 229 | pcl::toROSMsg(transform_cloud, pub_cloud); 230 | pub_cloud.header.frame_id = "camera_init"; 231 | pubCureentCloud.publish(pub_cloud); 232 | 233 | pcl::PointCloud key_points_cloud; 234 | for (auto var : btc_manager->history_binary_list_.back()) { 235 | pcl::PointXYZ pi; 236 | pi.x = var.location_[0]; 237 | pi.y = var.location_[1]; 238 | pi.z = var.location_[2]; 239 | key_points_cloud.push_back(pi); 240 | } 241 | pcl::toROSMsg(key_points_cloud, pub_cloud); 242 | pub_cloud.header.frame_id = "camera_init"; 243 | pubCurrentBinary.publish(pub_cloud); 244 | 245 | visualization_msgs::MarkerArray marker_array; 246 | visualization_msgs::Marker marker; 247 | marker.header.frame_id = "camera_init"; 248 | marker.ns = "colored_path"; 249 | marker.id = submap_id; 250 | marker.type = visualization_msgs::Marker::LINE_LIST; 251 | marker.action = visualization_msgs::Marker::ADD; 252 | marker.pose.orientation.w = 1.0; 253 | if (search_result.first >= 0) { 254 | triggle_loop_num++; 255 | Eigen::Matrix4d transform1 = Eigen::Matrix4d::Identity(); 256 | Eigen::Matrix4d transform2 = Eigen::Matrix4d::Identity(); 257 | publish_std(loop_std_pair, transform1, transform2, pubBTC); 258 | slow_loop.sleep(); 259 | double cloud_overlap = 260 | calc_overlap(transform_cloud.makeShared(), 261 | btc_manager->key_cloud_vec_[search_result.first], 0.5); 262 | pcl::PointCloud match_key_points_cloud; 263 | for (auto var : 264 | btc_manager->history_binary_list_[search_result.first]) { 265 | pcl::PointXYZ pi; 266 | pi.x = var.location_[0]; 267 | pi.y = var.location_[1]; 268 | pi.z = var.location_[2]; 269 | match_key_points_cloud.push_back(pi); 270 | } 271 | pcl::toROSMsg(match_key_points_cloud, pub_cloud); 272 | pub_cloud.header.frame_id = "camera_init"; 273 | pubMatchedBinary.publish(pub_cloud); 274 | // true positive 275 | if (cloud_overlap >= cloud_overlap_thr) { 276 | true_loop_num++; 277 | pcl::PointCloud matched_cloud; 278 | matched_cloud.resize( 279 | btc_manager->key_cloud_vec_[search_result.first]->size()); 280 | for (size_t i = 0; 281 | i < btc_manager->key_cloud_vec_[search_result.first]->size(); 282 | i++) { 283 | pcl::PointXYZRGB pi; 284 | pi.x = 285 | btc_manager->key_cloud_vec_[search_result.first]->points[i].x; 286 | pi.y = 287 | btc_manager->key_cloud_vec_[search_result.first]->points[i].y; 288 | pi.z = 289 | btc_manager->key_cloud_vec_[search_result.first]->points[i].z; 290 | pi.r = 0; 291 | pi.g = 255; 292 | pi.b = 0; 293 | matched_cloud.points[i] = pi; 294 | } 295 | pcl::toROSMsg(matched_cloud, pub_cloud); 296 | pub_cloud.header.frame_id = "camera_init"; 297 | pubMatchedCloud.publish(pub_cloud); 298 | slow_loop.sleep(); 299 | 300 | marker.scale.x = scale_tp; 301 | marker.color = color_tp; 302 | geometry_msgs::Point point1; 303 | point1.x = pose_list[submap_id - 1].first[0]; 304 | point1.y = pose_list[submap_id - 1].first[1]; 305 | point1.z = pose_list[submap_id - 1].first[2]; 306 | geometry_msgs::Point point2; 307 | point2.x = pose_list[submap_id].first[0]; 308 | point2.y = pose_list[submap_id].first[1]; 309 | point2.z = pose_list[submap_id].first[2]; 310 | marker.points.push_back(point1); 311 | marker.points.push_back(point2); 312 | 313 | } else { 314 | pcl::PointCloud matched_cloud; 315 | matched_cloud.resize( 316 | btc_manager->key_cloud_vec_[search_result.first]->size()); 317 | for (size_t i = 0; 318 | i < btc_manager->key_cloud_vec_[search_result.first]->size(); 319 | i++) { 320 | pcl::PointXYZRGB pi; 321 | pi.x = 322 | btc_manager->key_cloud_vec_[search_result.first]->points[i].x; 323 | pi.y = 324 | btc_manager->key_cloud_vec_[search_result.first]->points[i].y; 325 | pi.z = 326 | btc_manager->key_cloud_vec_[search_result.first]->points[i].z; 327 | pi.r = 255; 328 | pi.g = 0; 329 | pi.b = 0; 330 | matched_cloud.points[i] = pi; 331 | } 332 | pcl::toROSMsg(matched_cloud, pub_cloud); 333 | pub_cloud.header.frame_id = "camera_init"; 334 | pubMatchedCloud.publish(pub_cloud); 335 | slow_loop.sleep(); 336 | marker.scale.x = scale_fp; 337 | marker.color = color_fp; 338 | geometry_msgs::Point point1; 339 | point1.x = pose_list[submap_id - 1].first[0]; 340 | point1.y = pose_list[submap_id - 1].first[1]; 341 | point1.z = pose_list[submap_id - 1].first[2]; 342 | geometry_msgs::Point point2; 343 | point2.x = pose_list[submap_id].first[0]; 344 | point2.y = pose_list[submap_id].first[1]; 345 | point2.z = pose_list[submap_id].first[2]; 346 | marker.points.push_back(point1); 347 | marker.points.push_back(point2); 348 | } 349 | 350 | } else { 351 | if (submap_id > 0) { 352 | marker.scale.x = scale_path; 353 | marker.color = color_path; 354 | geometry_msgs::Point point1; 355 | point1.x = pose_list[submap_id - 1].first[0]; 356 | point1.y = pose_list[submap_id - 1].first[1]; 357 | point1.z = pose_list[submap_id - 1].first[2]; 358 | geometry_msgs::Point point2; 359 | point2.x = pose_list[submap_id].first[0]; 360 | point2.y = pose_list[submap_id].first[1]; 361 | point2.z = pose_list[submap_id].first[2]; 362 | marker.points.push_back(point1); 363 | marker.points.push_back(point2); 364 | } 365 | } 366 | marker_array.markers.push_back(marker); 367 | pubLoopStatus.publish(marker_array); 368 | loop.sleep(); 369 | } 370 | finish = true; 371 | } 372 | 373 | double mean_descriptor_time = 374 | std::accumulate(descriptor_time.begin(), descriptor_time.end(), 0) * 1.0 / 375 | descriptor_time.size(); 376 | double mean_query_time = 377 | std::accumulate(querying_time.begin(), querying_time.end(), 0) * 1.0 / 378 | querying_time.size(); 379 | double mean_update_time = 380 | std::accumulate(update_time.begin(), update_time.end(), 0) * 1.0 / 381 | update_time.size(); 382 | std::cout << "Total submap number:" << pose_list.size() 383 | << ", triggle loop number:" << triggle_loop_num 384 | << ", true loop number:" << true_loop_num << std::endl; 385 | std::cout << "Mean time for descriptor extraction: " << mean_descriptor_time 386 | << "ms, query: " << mean_query_time 387 | << "ms, update: " << mean_update_time << "ms, total: " 388 | << mean_descriptor_time + mean_query_time + mean_update_time << "ms" 389 | << std::endl; 390 | return 0; 391 | } -------------------------------------------------------------------------------- /figs/system_pipeline_btc.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/btc_descriptor/742af157036144edad9a8350330c0158ea1a40d5/figs/system_pipeline_btc.png -------------------------------------------------------------------------------- /figs/video_cover.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/btc_descriptor/742af157036144edad9a8350330c0158ea1a40d5/figs/video_cover.jpg -------------------------------------------------------------------------------- /include/CustomMsg.h: -------------------------------------------------------------------------------- 1 | // Generated by gencpp from file livox_ros_driver/CustomMsg.msg 2 | // DO NOT EDIT! 3 | 4 | 5 | #ifndef LIVOX_ROS_DRIVER_MESSAGE_CUSTOMMSG_H 6 | #define LIVOX_ROS_DRIVER_MESSAGE_CUSTOMMSG_H 7 | 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | #include 19 | #include "CustomPoint.h" 20 | 21 | namespace livox_ros_driver 22 | { 23 | template 24 | struct CustomMsg_ 25 | { 26 | typedef CustomMsg_ Type; 27 | 28 | CustomMsg_() 29 | : header() 30 | , timebase(0) 31 | , point_num(0) 32 | , lidar_id(0) 33 | , rsvd() 34 | , points() { 35 | rsvd.assign(0); 36 | } 37 | CustomMsg_(const ContainerAllocator& _alloc) 38 | : header(_alloc) 39 | , timebase(0) 40 | , point_num(0) 41 | , lidar_id(0) 42 | , rsvd() 43 | , points(_alloc) { 44 | (void)_alloc; 45 | rsvd.assign(0); 46 | } 47 | 48 | 49 | 50 | typedef ::std_msgs::Header_ _header_type; 51 | _header_type header; 52 | 53 | typedef uint64_t _timebase_type; 54 | _timebase_type timebase; 55 | 56 | typedef uint32_t _point_num_type; 57 | _point_num_type point_num; 58 | 59 | typedef uint8_t _lidar_id_type; 60 | _lidar_id_type lidar_id; 61 | 62 | typedef boost::array _rsvd_type; 63 | _rsvd_type rsvd; 64 | 65 | typedef std::vector< ::livox_ros_driver::CustomPoint_ , typename ContainerAllocator::template rebind< ::livox_ros_driver::CustomPoint_ >::other > _points_type; 66 | _points_type points; 67 | 68 | 69 | 70 | 71 | 72 | typedef boost::shared_ptr< ::livox_ros_driver::CustomMsg_ > Ptr; 73 | typedef boost::shared_ptr< ::livox_ros_driver::CustomMsg_ const> ConstPtr; 74 | 75 | }; // struct CustomMsg_ 76 | 77 | typedef ::livox_ros_driver::CustomMsg_ > CustomMsg; 78 | 79 | typedef boost::shared_ptr< ::livox_ros_driver::CustomMsg > CustomMsgPtr; 80 | typedef boost::shared_ptr< ::livox_ros_driver::CustomMsg const> CustomMsgConstPtr; 81 | 82 | // constants requiring out of line definition 83 | 84 | 85 | 86 | template 87 | std::ostream& operator<<(std::ostream& s, const ::livox_ros_driver::CustomMsg_ & v) 88 | { 89 | ros::message_operations::Printer< ::livox_ros_driver::CustomMsg_ >::stream(s, "", v); 90 | return s; 91 | } 92 | 93 | } // namespace livox_ros_driver 94 | 95 | namespace ros 96 | { 97 | namespace message_traits 98 | { 99 | 100 | 101 | 102 | // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} 103 | // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'livox_ros_driver': ['/home/dji/Documents/data_set/src/livox_ros_driver/livox_ros_driver/msg']} 104 | 105 | // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] 106 | 107 | 108 | 109 | 110 | template 111 | struct IsFixedSize< ::livox_ros_driver::CustomMsg_ > 112 | : FalseType 113 | { }; 114 | 115 | template 116 | struct IsFixedSize< ::livox_ros_driver::CustomMsg_ const> 117 | : FalseType 118 | { }; 119 | 120 | template 121 | struct IsMessage< ::livox_ros_driver::CustomMsg_ > 122 | : TrueType 123 | { }; 124 | 125 | template 126 | struct IsMessage< ::livox_ros_driver::CustomMsg_ const> 127 | : TrueType 128 | { }; 129 | 130 | template 131 | struct HasHeader< ::livox_ros_driver::CustomMsg_ > 132 | : TrueType 133 | { }; 134 | 135 | template 136 | struct HasHeader< ::livox_ros_driver::CustomMsg_ const> 137 | : TrueType 138 | { }; 139 | 140 | 141 | template 142 | struct MD5Sum< ::livox_ros_driver::CustomMsg_ > 143 | { 144 | static const char* value() 145 | { 146 | return "e4d6829bdfe657cb6c21a746c86b21a6"; 147 | } 148 | 149 | static const char* value(const ::livox_ros_driver::CustomMsg_&) { return value(); } 150 | static const uint64_t static_value1 = 0xe4d6829bdfe657cbULL; 151 | static const uint64_t static_value2 = 0x6c21a746c86b21a6ULL; 152 | }; 153 | 154 | template 155 | struct DataType< ::livox_ros_driver::CustomMsg_ > 156 | { 157 | static const char* value() 158 | { 159 | return "livox_ros_driver/CustomMsg"; 160 | } 161 | 162 | static const char* value(const ::livox_ros_driver::CustomMsg_&) { return value(); } 163 | }; 164 | 165 | template 166 | struct Definition< ::livox_ros_driver::CustomMsg_ > 167 | { 168 | static const char* value() 169 | { 170 | return "# Livox publish pointcloud msg format.\n\ 171 | \n\ 172 | Header header # ROS standard message header\n\ 173 | uint64 timebase # The time of first point\n\ 174 | uint32 point_num # Total number of pointclouds\n\ 175 | uint8 lidar_id # Lidar device id number\n\ 176 | uint8[3] rsvd # Reserved use\n\ 177 | CustomPoint[] points # Pointcloud data\n\ 178 | \n\ 179 | \n\ 180 | ================================================================================\n\ 181 | MSG: std_msgs/Header\n\ 182 | # Standard metadata for higher-level stamped data types.\n\ 183 | # This is generally used to communicate timestamped data \n\ 184 | # in a particular coordinate frame.\n\ 185 | # \n\ 186 | # sequence ID: consecutively increasing ID \n\ 187 | uint32 seq\n\ 188 | #Two-integer timestamp that is expressed as:\n\ 189 | # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 190 | # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 191 | # time-handling sugar is provided by the client library\n\ 192 | time stamp\n\ 193 | #Frame this data is associated with\n\ 194 | # 0: no frame\n\ 195 | # 1: global frame\n\ 196 | string frame_id\n\ 197 | \n\ 198 | ================================================================================\n\ 199 | MSG: livox_ros_driver/CustomPoint\n\ 200 | # Livox costom pointcloud format.\n\ 201 | \n\ 202 | uint32 offset_time # offset time relative to the base time\n\ 203 | float32 x # X axis, unit:m\n\ 204 | float32 y # Y axis, unit:m\n\ 205 | float32 z # Z axis, unit:m\n\ 206 | uint8 reflectivity # reflectivity, 0~255\n\ 207 | uint8 tag # livox tag\n\ 208 | uint8 line # laser number in lidar\n\ 209 | \n\ 210 | "; 211 | } 212 | 213 | static const char* value(const ::livox_ros_driver::CustomMsg_&) { return value(); } 214 | }; 215 | 216 | } // namespace message_traits 217 | } // namespace ros 218 | 219 | namespace ros 220 | { 221 | namespace serialization 222 | { 223 | 224 | template struct Serializer< ::livox_ros_driver::CustomMsg_ > 225 | { 226 | template inline static void allInOne(Stream& stream, T m) 227 | { 228 | stream.next(m.header); 229 | stream.next(m.timebase); 230 | stream.next(m.point_num); 231 | stream.next(m.lidar_id); 232 | stream.next(m.rsvd); 233 | stream.next(m.points); 234 | } 235 | 236 | ROS_DECLARE_ALLINONE_SERIALIZER 237 | }; // struct CustomMsg_ 238 | 239 | } // namespace serialization 240 | } // namespace ros 241 | 242 | namespace ros 243 | { 244 | namespace message_operations 245 | { 246 | 247 | template 248 | struct Printer< ::livox_ros_driver::CustomMsg_ > 249 | { 250 | template static void stream(Stream& s, const std::string& indent, const ::livox_ros_driver::CustomMsg_& v) 251 | { 252 | s << indent << "header: "; 253 | s << std::endl; 254 | Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); 255 | s << indent << "timebase: "; 256 | Printer::stream(s, indent + " ", v.timebase); 257 | s << indent << "point_num: "; 258 | Printer::stream(s, indent + " ", v.point_num); 259 | s << indent << "lidar_id: "; 260 | Printer::stream(s, indent + " ", v.lidar_id); 261 | s << indent << "rsvd[]" << std::endl; 262 | for (size_t i = 0; i < v.rsvd.size(); ++i) 263 | { 264 | s << indent << " rsvd[" << i << "]: "; 265 | Printer::stream(s, indent + " ", v.rsvd[i]); 266 | } 267 | s << indent << "points[]" << std::endl; 268 | for (size_t i = 0; i < v.points.size(); ++i) 269 | { 270 | s << indent << " points[" << i << "]: "; 271 | s << std::endl; 272 | s << indent; 273 | Printer< ::livox_ros_driver::CustomPoint_ >::stream(s, indent + " ", v.points[i]); 274 | } 275 | } 276 | }; 277 | 278 | } // namespace message_operations 279 | } // namespace ros 280 | 281 | #endif // LIVOX_ROS_DRIVER_MESSAGE_CUSTOMMSG_H 282 | -------------------------------------------------------------------------------- /include/CustomPoint.h: -------------------------------------------------------------------------------- 1 | // Generated by gencpp from file livox_ros_driver/CustomPoint.msg 2 | // DO NOT EDIT! 3 | 4 | 5 | #ifndef LIVOX_ROS_DRIVER_MESSAGE_CUSTOMPOINT_H 6 | #define LIVOX_ROS_DRIVER_MESSAGE_CUSTOMPOINT_H 7 | 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | 19 | namespace livox_ros_driver 20 | { 21 | template 22 | struct CustomPoint_ 23 | { 24 | typedef CustomPoint_ Type; 25 | 26 | CustomPoint_() 27 | : offset_time(0) 28 | , x(0.0) 29 | , y(0.0) 30 | , z(0.0) 31 | , reflectivity(0) 32 | , tag(0) 33 | , line(0) { 34 | } 35 | CustomPoint_(const ContainerAllocator& _alloc) 36 | : offset_time(0) 37 | , x(0.0) 38 | , y(0.0) 39 | , z(0.0) 40 | , reflectivity(0) 41 | , tag(0) 42 | , line(0) { 43 | (void)_alloc; 44 | } 45 | 46 | 47 | 48 | typedef uint32_t _offset_time_type; 49 | _offset_time_type offset_time; 50 | 51 | typedef float _x_type; 52 | _x_type x; 53 | 54 | typedef float _y_type; 55 | _y_type y; 56 | 57 | typedef float _z_type; 58 | _z_type z; 59 | 60 | typedef uint8_t _reflectivity_type; 61 | _reflectivity_type reflectivity; 62 | 63 | typedef uint8_t _tag_type; 64 | _tag_type tag; 65 | 66 | typedef uint8_t _line_type; 67 | _line_type line; 68 | 69 | 70 | 71 | 72 | 73 | typedef boost::shared_ptr< ::livox_ros_driver::CustomPoint_ > Ptr; 74 | typedef boost::shared_ptr< ::livox_ros_driver::CustomPoint_ const> ConstPtr; 75 | 76 | }; // struct CustomPoint_ 77 | 78 | typedef ::livox_ros_driver::CustomPoint_ > CustomPoint; 79 | 80 | typedef boost::shared_ptr< ::livox_ros_driver::CustomPoint > CustomPointPtr; 81 | typedef boost::shared_ptr< ::livox_ros_driver::CustomPoint const> CustomPointConstPtr; 82 | 83 | // constants requiring out of line definition 84 | 85 | 86 | 87 | template 88 | std::ostream& operator<<(std::ostream& s, const ::livox_ros_driver::CustomPoint_ & v) 89 | { 90 | ros::message_operations::Printer< ::livox_ros_driver::CustomPoint_ >::stream(s, "", v); 91 | return s; 92 | } 93 | 94 | } // namespace livox_ros_driver 95 | 96 | namespace ros 97 | { 98 | namespace message_traits 99 | { 100 | 101 | 102 | 103 | // BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} 104 | // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'livox_ros_driver': ['/home/dji/Documents/data_set/src/livox_ros_driver/livox_ros_driver/msg']} 105 | 106 | // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] 107 | 108 | 109 | 110 | 111 | template 112 | struct IsFixedSize< ::livox_ros_driver::CustomPoint_ > 113 | : TrueType 114 | { }; 115 | 116 | template 117 | struct IsFixedSize< ::livox_ros_driver::CustomPoint_ const> 118 | : TrueType 119 | { }; 120 | 121 | template 122 | struct IsMessage< ::livox_ros_driver::CustomPoint_ > 123 | : TrueType 124 | { }; 125 | 126 | template 127 | struct IsMessage< ::livox_ros_driver::CustomPoint_ const> 128 | : TrueType 129 | { }; 130 | 131 | template 132 | struct HasHeader< ::livox_ros_driver::CustomPoint_ > 133 | : FalseType 134 | { }; 135 | 136 | template 137 | struct HasHeader< ::livox_ros_driver::CustomPoint_ const> 138 | : FalseType 139 | { }; 140 | 141 | 142 | template 143 | struct MD5Sum< ::livox_ros_driver::CustomPoint_ > 144 | { 145 | static const char* value() 146 | { 147 | return "109a3cc548bb1f96626be89a5008bd6d"; 148 | } 149 | 150 | static const char* value(const ::livox_ros_driver::CustomPoint_&) { return value(); } 151 | static const uint64_t static_value1 = 0x109a3cc548bb1f96ULL; 152 | static const uint64_t static_value2 = 0x626be89a5008bd6dULL; 153 | }; 154 | 155 | template 156 | struct DataType< ::livox_ros_driver::CustomPoint_ > 157 | { 158 | static const char* value() 159 | { 160 | return "livox_ros_driver/CustomPoint"; 161 | } 162 | 163 | static const char* value(const ::livox_ros_driver::CustomPoint_&) { return value(); } 164 | }; 165 | 166 | template 167 | struct Definition< ::livox_ros_driver::CustomPoint_ > 168 | { 169 | static const char* value() 170 | { 171 | return "# Livox costom pointcloud format.\n\ 172 | \n\ 173 | uint32 offset_time # offset time relative to the base time\n\ 174 | float32 x # X axis, unit:m\n\ 175 | float32 y # Y axis, unit:m\n\ 176 | float32 z # Z axis, unit:m\n\ 177 | uint8 reflectivity # reflectivity, 0~255\n\ 178 | uint8 tag # livox tag\n\ 179 | uint8 line # laser number in lidar\n\ 180 | \n\ 181 | "; 182 | } 183 | 184 | static const char* value(const ::livox_ros_driver::CustomPoint_&) { return value(); } 185 | }; 186 | 187 | } // namespace message_traits 188 | } // namespace ros 189 | 190 | namespace ros 191 | { 192 | namespace serialization 193 | { 194 | 195 | template struct Serializer< ::livox_ros_driver::CustomPoint_ > 196 | { 197 | template inline static void allInOne(Stream& stream, T m) 198 | { 199 | stream.next(m.offset_time); 200 | stream.next(m.x); 201 | stream.next(m.y); 202 | stream.next(m.z); 203 | stream.next(m.reflectivity); 204 | stream.next(m.tag); 205 | stream.next(m.line); 206 | } 207 | 208 | ROS_DECLARE_ALLINONE_SERIALIZER 209 | }; // struct CustomPoint_ 210 | 211 | } // namespace serialization 212 | } // namespace ros 213 | 214 | namespace ros 215 | { 216 | namespace message_operations 217 | { 218 | 219 | template 220 | struct Printer< ::livox_ros_driver::CustomPoint_ > 221 | { 222 | template static void stream(Stream& s, const std::string& indent, const ::livox_ros_driver::CustomPoint_& v) 223 | { 224 | s << indent << "offset_time: "; 225 | Printer::stream(s, indent + " ", v.offset_time); 226 | s << indent << "x: "; 227 | Printer::stream(s, indent + " ", v.x); 228 | s << indent << "y: "; 229 | Printer::stream(s, indent + " ", v.y); 230 | s << indent << "z: "; 231 | Printer::stream(s, indent + " ", v.z); 232 | s << indent << "reflectivity: "; 233 | Printer::stream(s, indent + " ", v.reflectivity); 234 | s << indent << "tag: "; 235 | Printer::stream(s, indent + " ", v.tag); 236 | s << indent << "line: "; 237 | Printer::stream(s, indent + " ", v.line); 238 | } 239 | }; 240 | 241 | } // namespace message_operations 242 | } // namespace ros 243 | 244 | #endif // LIVOX_ROS_DRIVER_MESSAGE_CUSTOMPOINT_H 245 | -------------------------------------------------------------------------------- /include/btc.h: -------------------------------------------------------------------------------- 1 | #ifndef BTC_H 2 | #define BTC_H 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #include 22 | #include 23 | #include 24 | 25 | #define HASH_P 116101 26 | #define MAX_N 10000000000 27 | 28 | typedef struct ConfigSetting { 29 | /* for submap process*/ 30 | double cloud_ds_size_ = 0.25; 31 | 32 | /* for binary descriptor*/ 33 | int useful_corner_num_ = 30; 34 | float plane_merge_normal_thre_; 35 | float plane_merge_dis_thre_; 36 | float plane_detection_thre_ = 0.01; 37 | float voxel_size_ = 1.0; 38 | int voxel_init_num_ = 10; 39 | int proj_plane_num_ = 1; 40 | float proj_image_resolution_ = 0.5; 41 | float proj_image_high_inc_ = 0.5; 42 | float proj_dis_min_ = 0; 43 | float proj_dis_max_ = 5; 44 | float summary_min_thre_ = 10; 45 | int line_filter_enable_ = 0; 46 | 47 | /* for triangle descriptor */ 48 | float descriptor_near_num_ = 10; 49 | float descriptor_min_len_ = 1; 50 | float descriptor_max_len_ = 10; 51 | float non_max_suppression_radius_ = 3.0; 52 | float std_side_resolution_ = 0.2; 53 | 54 | /* for place recognition*/ 55 | int skip_near_num_ = 20; 56 | int candidate_num_ = 50; 57 | int sub_frame_num_ = 10; 58 | float rough_dis_threshold_ = 0.03; 59 | float similarity_threshold_ = 0.7; 60 | float icp_threshold_ = 0.5; 61 | float normal_threshold_ = 0.1; 62 | float dis_threshold_ = 0.3; 63 | 64 | /* extrinsic for lidar to vehicle*/ 65 | Eigen::Matrix3d rot_lidar_to_vehicle_; 66 | Eigen::Vector3d t_lidar_to_vehicle_; 67 | 68 | /* for gt file style*/ 69 | int gt_file_style_ = 0; 70 | 71 | } ConfigSetting; 72 | 73 | typedef struct BinaryDescriptor { 74 | std::vector occupy_array_; 75 | unsigned char summary_; 76 | Eigen::Vector3d location_; 77 | } BinaryDescriptor; 78 | 79 | // Binary Triangle Descriptor 80 | typedef struct BTC { 81 | Eigen::Vector3d triangle_; 82 | Eigen::Vector3d angle_; 83 | Eigen::Vector3d center_; 84 | unsigned short frame_number_; 85 | BinaryDescriptor binary_A_; 86 | BinaryDescriptor binary_B_; 87 | BinaryDescriptor binary_C_; 88 | } BTC; 89 | 90 | typedef struct Plane { 91 | pcl::PointXYZINormal p_center_; 92 | Eigen::Vector3d center_; 93 | Eigen::Vector3d normal_; 94 | Eigen::Matrix3d covariance_; 95 | float radius_ = 0; 96 | float min_eigen_value_ = 1; 97 | float d_ = 0; 98 | int id_ = 0; 99 | int sub_plane_num_ = 0; 100 | int points_size_ = 0; 101 | bool is_plane_ = false; 102 | } Plane; 103 | 104 | typedef struct BTCMatchList { 105 | std::vector> match_list_; 106 | std::pair match_id_; 107 | int match_frame_; 108 | double mean_dis_; 109 | } BTCMatchList; 110 | 111 | struct M_POINT { 112 | float xyz[3]; 113 | float intensity; 114 | int count = 0; 115 | }; 116 | 117 | class VOXEL_LOC { 118 | public: 119 | int64_t x, y, z; 120 | 121 | VOXEL_LOC(int64_t vx = 0, int64_t vy = 0, int64_t vz = 0) 122 | : x(vx), y(vy), z(vz) {} 123 | 124 | bool operator==(const VOXEL_LOC &other) const { 125 | return (x == other.x && y == other.y && z == other.z); 126 | } 127 | }; 128 | 129 | // Hash value 130 | namespace std { 131 | template <> 132 | struct hash { 133 | int64 operator()(const VOXEL_LOC &s) const { 134 | using std::hash; 135 | using std::size_t; 136 | return ((((s.z) * HASH_P) % MAX_N + (s.y)) * HASH_P) % MAX_N + (s.x); 137 | } 138 | }; 139 | } // namespace std 140 | 141 | class BTC_LOC { 142 | public: 143 | int64_t x, y, z, a, b, c; 144 | 145 | BTC_LOC(int64_t vx = 0, int64_t vy = 0, int64_t vz = 0, int64_t va = 0, 146 | int64_t vb = 0, int64_t vc = 0) 147 | : x(vx), y(vy), z(vz), a(va), b(vb), c(vc) {} 148 | 149 | bool operator==(const BTC_LOC &other) const { 150 | return (x == other.x && y == other.y && z == other.z); 151 | // return (x == other.x && y == other.y && z == other.z && a == other.a && 152 | // b == other.b && c == other.c); 153 | } 154 | }; 155 | 156 | namespace std { 157 | template <> 158 | struct hash { 159 | int64 operator()(const BTC_LOC &s) const { 160 | using std::hash; 161 | using std::size_t; 162 | return ((((s.z) * HASH_P) % MAX_N + (s.y)) * HASH_P) % MAX_N + (s.x); 163 | } 164 | }; 165 | } // namespace std 166 | 167 | class OctoTree { 168 | public: 169 | ConfigSetting config_setting_; 170 | std::vector voxel_points_; 171 | std::shared_ptr plane_ptr_; 172 | int layer_; 173 | int octo_state_; // 0 is end of tree, 1 is not 174 | int merge_num_ = 0; 175 | bool is_project_ = false; 176 | std::vector project_normal; 177 | bool is_publish_ = false; 178 | OctoTree *leaves_[8]; 179 | double voxel_center_[3]; // x, y, z 180 | float quater_length_; 181 | bool init_octo_; 182 | 183 | // for plot 184 | bool is_check_connect_[6]; 185 | bool connect_[6]; 186 | OctoTree *connect_tree_[6]; 187 | 188 | OctoTree(const ConfigSetting &config_setting) 189 | : config_setting_(config_setting) { 190 | voxel_points_.clear(); 191 | octo_state_ = 0; 192 | layer_ = 0; 193 | init_octo_ = false; 194 | for (int i = 0; i < 8; i++) { 195 | leaves_[i] = nullptr; 196 | } 197 | // for plot 198 | for (int i = 0; i < 6; i++) { 199 | is_check_connect_[i] = false; 200 | connect_[i] = false; 201 | connect_tree_[i] = nullptr; 202 | } 203 | plane_ptr_.reset(new Plane); 204 | } 205 | void init_plane(); 206 | void init_octo_tree(); 207 | }; 208 | 209 | void down_sampling_voxel(pcl::PointCloud &pl_feat, 210 | double voxel_size); 211 | 212 | void load_config_setting(std::string &config_file, 213 | ConfigSetting &config_setting); 214 | 215 | double binary_similarity(const BinaryDescriptor &b1, 216 | const BinaryDescriptor &b2); 217 | 218 | bool binary_greater_sort(BinaryDescriptor a, BinaryDescriptor b); 219 | bool plane_greater_sort(std::shared_ptr plane1, 220 | std::shared_ptr plane2); 221 | 222 | void publish_std(const std::vector> &match_std_list, 223 | const Eigen::Matrix4d &transform1, 224 | const Eigen::Matrix4d &transform2, 225 | const ros::Publisher &std_publisher); 226 | 227 | void publish_std_list(const std::vector &btc_list, 228 | const ros::Publisher &std_publisher); 229 | 230 | void publish_binary(const std::vector &binary_list, 231 | const Eigen::Vector3d &text_color, 232 | const std::string &text_ns, 233 | const ros::Publisher &text_publisher); 234 | 235 | double calc_triangle_dis( 236 | const std::vector> &match_std_list); 237 | 238 | double calc_binary_similaity( 239 | const std::vector> &match_std_list); 240 | 241 | void CalcQuation(const Eigen::Vector3d &vec, const int axis, 242 | geometry_msgs::Quaternion &q); 243 | 244 | void pubPlane(const ros::Publisher &plane_pub, const std::string plane_ns, 245 | const int plane_id, const pcl::PointXYZINormal normal_p, 246 | const float radius, const Eigen::Vector3d rgb); 247 | 248 | struct PlaneSolver { 249 | PlaneSolver(Eigen::Vector3d curr_point_, Eigen::Vector3d curr_normal_, 250 | Eigen::Vector3d target_point_, Eigen::Vector3d target_normal_) 251 | : curr_point(curr_point_), 252 | curr_normal(curr_normal_), 253 | target_point(target_point_), 254 | target_normal(target_normal_) {}; 255 | template 256 | bool operator()(const T *q, const T *t, T *residual) const { 257 | Eigen::Quaternion q_w_curr{q[3], q[0], q[1], q[2]}; 258 | Eigen::Matrix t_w_curr{t[0], t[1], t[2]}; 259 | Eigen::Matrix cp{T(curr_point.x()), T(curr_point.y()), 260 | T(curr_point.z())}; 261 | Eigen::Matrix point_w; 262 | point_w = q_w_curr * cp + t_w_curr; 263 | Eigen::Matrix point_target( 264 | T(target_point.x()), T(target_point.y()), T(target_point.z())); 265 | Eigen::Matrix norm(T(target_normal.x()), T(target_normal.y()), 266 | T(target_normal.z())); 267 | residual[0] = norm.dot(point_w - point_target); 268 | return true; 269 | } 270 | 271 | static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_, 272 | const Eigen::Vector3d curr_normal_, 273 | Eigen::Vector3d target_point_, 274 | Eigen::Vector3d target_normal_) { 275 | return ( 276 | new ceres::AutoDiffCostFunction(new PlaneSolver( 277 | curr_point_, curr_normal_, target_point_, target_normal_))); 278 | } 279 | 280 | Eigen::Vector3d curr_point; 281 | Eigen::Vector3d curr_normal; 282 | Eigen::Vector3d target_point; 283 | Eigen::Vector3d target_normal; 284 | }; 285 | 286 | class BtcDescManager { 287 | public: 288 | BtcDescManager() = default; 289 | 290 | ConfigSetting config_setting_; 291 | 292 | BtcDescManager(ConfigSetting &config_setting) 293 | : config_setting_(config_setting) {}; 294 | 295 | // if print debug info 296 | bool print_debug_info_ = false; 297 | 298 | // hash table, save all descriptors 299 | std::unordered_map> data_base_; 300 | 301 | // save all key clouds, optional 302 | std::vector::Ptr> key_cloud_vec_; 303 | 304 | // save all binary descriptors of key frame 305 | std::vector> history_binary_list_; 306 | 307 | // save all planes of key frame, required 308 | std::vector::Ptr> plane_cloud_vec_; 309 | 310 | /*Three main processing functions*/ 311 | 312 | // generate BtcDescs from a point cloud 313 | void GenerateBtcDescs(const pcl::PointCloud::Ptr &input_cloud, 314 | const int frame_id, std::vector &btcs_vec); 315 | 316 | // search result . -1 for no loop 317 | void SearchLoop(const std::vector &btcs_vec, 318 | std::pair &loop_result, 319 | std::pair &loop_transform, 320 | std::vector> &loop_std_pair); 321 | 322 | // add descriptors to database 323 | void AddBtcDescs(const std::vector &btcs_vec); 324 | 325 | // Geometrical optimization by plane-to-plane icp 326 | void PlaneGeomrtricIcp( 327 | const pcl::PointCloud::Ptr &source_cloud, 328 | const pcl::PointCloud::Ptr &target_cloud, 329 | std::pair &transform); 330 | 331 | private: 332 | /*Following are sub-processing functions*/ 333 | 334 | // voxelization and plane detection 335 | void init_voxel_map(const pcl::PointCloud::Ptr &input_cloud, 336 | std::unordered_map &voxel_map); 337 | 338 | // acquire planes from voxel_map 339 | void get_plane(const std::unordered_map &voxel_map, 340 | pcl::PointCloud::Ptr &plane_cloud); 341 | 342 | void get_project_plane( 343 | std::unordered_map &feat_map, 344 | std::vector> &project_plane_list); 345 | 346 | void merge_plane(std::vector> &origin_list, 347 | std::vector> &merge_plane_list); 348 | 349 | // extract corner points from pre-build voxel map and clouds 350 | 351 | void binary_extractor( 352 | const std::vector> proj_plane_list, 353 | const pcl::PointCloud::Ptr &input_cloud, 354 | std::vector &binary_descriptor_list); 355 | 356 | void extract_binary(const Eigen::Vector3d &project_center, 357 | const Eigen::Vector3d &project_normal, 358 | const pcl::PointCloud::Ptr &input_cloud, 359 | std::vector &binary_list); 360 | 361 | // non maximum suppression, to control the number of corners 362 | void non_maxi_suppression(std::vector &binary_list); 363 | 364 | // build BTCs from corner points. 365 | void generate_btc(const std::vector &binary_list, 366 | const int &frame_id, std::vector &btc_list); 367 | 368 | // Select a specified number of candidate frames according to the number of 369 | // BtcDescs rough matches 370 | void candidate_selector(const std::vector &btcs_vec, 371 | std::vector &candidate_matcher_vec); 372 | 373 | // Get the best candidate frame by geometry check 374 | void candidate_verify( 375 | const BTCMatchList &candidate_matcher, double &verify_score, 376 | std::pair &relative_pose, 377 | std::vector> &sucess_match_vec); 378 | 379 | // Get the transform between a matched std pair 380 | void triangle_solver(std::pair &std_pair, Eigen::Vector3d &t, 381 | Eigen::Matrix3d &rot); 382 | 383 | // Geometrical verification by plane-to-plane icp threshold 384 | double plane_geometric_verify( 385 | const pcl::PointCloud::Ptr &source_cloud, 386 | const pcl::PointCloud::Ptr &target_cloud, 387 | const std::pair &transform); 388 | }; 389 | 390 | #endif // BTC_H -------------------------------------------------------------------------------- /include/utils.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef UTILS_H 3 | #define UTILS_H 4 | #include 5 | #include 6 | #include 7 | 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | void load_pose_with_time( 14 | const std::string &pose_file, 15 | std::vector> &pose_list, 16 | std::vector &time_list); 17 | 18 | void load_evo_pose_with_time( 19 | const std::string &pose_file, 20 | std::vector> &pose_list, 21 | std::vector &time_list); 22 | 23 | void load_cu_pose_with_time( 24 | const std::string &pose_file, 25 | std::vector> &pose_list, 26 | std::vector &time_list); 27 | 28 | void load_pose_with_frame( 29 | const std::string &pose_file, 30 | std::vector> &pose_list, 31 | std::vector &frame_number_list); 32 | 33 | int findPoseIndexUsingTime(std::vector &time_list, double &time); 34 | 35 | pcl::PointXYZI vec2point(const Eigen::Vector3d &vec); 36 | // Eigen::Vector3d point2vec(const pcl::PointXYZI &pi); 37 | 38 | Eigen::Vector3d normal2vec(const pcl::PointXYZINormal &pi); 39 | 40 | template 41 | Eigen::Vector3d point2vec(const T &pi) { 42 | Eigen::Vector3d vec(pi.x, pi.y, pi.z); 43 | return vec; 44 | } 45 | 46 | double time_inc(std::chrono::_V2::system_clock::time_point &t_end, 47 | std::chrono::_V2::system_clock::time_point &t_begin); 48 | 49 | double calc_overlap(const pcl::PointCloud::Ptr &cloud1, 50 | const pcl::PointCloud::Ptr &cloud2, 51 | double dis_threshold); 52 | 53 | double calc_overlap(const pcl::PointCloud::Ptr &cloud1, 54 | const pcl::PointCloud::Ptr &cloud2, 55 | double dis_threshold, int skip_num); 56 | 57 | #endif -------------------------------------------------------------------------------- /launch/place_recognition.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | btc_desc 4 | 1.0.0 5 | The btc_desc package 6 | 7 | 8 | 9 | 10 | ycj 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | catkin 52 | cv_bridge 53 | libpcl-all-dev 54 | roscpp 55 | rospy 56 | sensor_msgs 57 | std_msgs 58 | cv_bridge 59 | libpcl-all-dev 60 | roscpp 61 | rospy 62 | sensor_msgs 63 | std_msgs 64 | tf_conversions 65 | cv_bridge 66 | libpcl-all 67 | roscpp 68 | rospy 69 | sensor_msgs 70 | std_msgs 71 | tf_conversions 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | -------------------------------------------------------------------------------- /poses/kitti07.txt: -------------------------------------------------------------------------------- 1 | 0 3.10098e-13 1.59101e-12 -6.46348e-16 1.39859e-11 1.33292e-11 -7.90653e-11 1 2 | 1 0.0406738 0.0060215 0.0038619 -0.000243 0.0001344 0.0033677 0.999994 3 | 2 0.0806745 0.00602145 0.00386191 -0.000243003 0.000134399 0.00336774 0.999994 4 | 3 0.167947 0.0120204 0.00764675 -0.000196914 -7.45961e-05 0.0072607 0.999974 5 | 4 0.268041 0.0253289 0.00826726 -0.000424841 -0.000708177 0.0118666 0.999929 6 | 5 0.391054 0.039242 0.00911566 -0.000540674 -0.00155606 0.0174742 0.999846 7 | 6 0.520179 0.0543646 0.00814336 -0.000485213 -0.00212654 0.0242341 0.999704 8 | 7 0.657157 0.0735055 0.00706628 -0.000496264 -0.00220923 0.0324352 0.999471 9 | 8 0.812567 0.0964751 0.008365 5.31735e-05 -0.00231551 0.0416351 0.99913 10 | 9 0.978205 0.12103 0.015095 0.000945092 -0.00234333 0.0516998 0.998659 11 | 10 1.13967 0.153359 0.0172369 0.000599094 -0.00269726 0.062894 0.998016 12 | 11 1.31968 0.205234 0.0221333 -0.000819626 -0.00337273 0.0749382 0.997182 13 | 12 1.49789 0.265032 0.0272592 -0.00308336 -0.00450022 0.087936 0.996111 14 | 13 1.67294 0.325557 0.032314 -0.00481243 -0.00528282 0.101541 0.994806 15 | 14 1.87313 0.395807 0.0399188 -0.00521983 -0.00562793 0.116458 0.993166 16 | 15 2.06179 0.461544 0.0433954 -0.00598846 -0.00585795 0.132224 0.991184 17 | 16 2.26707 0.558585 0.0431614 -0.00671212 -0.00579207 0.148489 0.988874 18 | 17 2.45978 0.653181 0.0531905 -0.00789903 -0.00553307 0.165935 0.986089 19 | 18 2.64413 0.742981 0.0509707 -0.00913496 -0.00594238 0.183594 0.982942 20 | 19 2.85616 0.869687 0.0515127 -0.0109435 -0.00618272 0.201073 0.979496 21 | 20 3.05745 0.991707 0.0477708 -0.0112802 -0.00649441 0.219677 0.975486 22 | 21 3.23957 1.10116 0.0464232 -0.00948309 -0.00683641 0.239561 0.970811 23 | 22 3.44381 1.24571 0.058458 -0.00742612 -0.00676868 0.26036 0.965459 24 | 23 3.62629 1.39065 0.0675306 -0.00784076 -0.00581862 0.282902 0.959099 25 | 24 3.81773 1.58149 0.0662798 -0.0101578 -0.00519732 0.306866 0.951684 26 | 25 3.99459 1.77669 0.0719319 -0.0120712 -0.005195 0.331752 0.943275 27 | 26 4.15626 1.95812 0.0663573 -0.0117815 -0.00563097 0.357341 0.933883 28 | 27 4.34694 2.18754 0.0794539 -0.00952761 -0.00454617 0.383667 0.923411 29 | 28 4.51801 2.41746 0.0830459 -0.00746999 -0.00370047 0.410166 0.911973 30 | 29 4.66658 2.64633 0.0843498 -0.00658605 -0.00273181 0.436305 0.899771 31 | 30 4.83127 2.93424 0.0821333 -0.00602573 -0.00148994 0.462666 0.886511 32 | 31 4.97266 3.21874 0.0852487 -0.00599204 -0.000714436 0.489158 0.872174 33 | 32 5.08978 3.50439 0.0813248 -0.00628521 6.62042e-05 0.515032 0.857148 34 | 33 5.21583 3.85281 0.0829533 -0.00660198 0.00119472 0.540687 0.841197 35 | 34 5.30698 4.1747 0.0794204 -0.00714414 0.00178847 0.56544 0.824756 36 | 35 5.40581 4.55668 0.079546 -0.00743633 0.00325861 0.589288 0.807882 37 | 36 5.47655 4.94111 0.0803517 -0.0067919 0.0052425 0.611602 0.791119 38 | 37 5.53087 5.30762 0.0898837 -0.00642867 0.0061735 0.631962 0.774948 39 | 38 5.57497 5.72833 0.0825293 -0.00736614 0.00538719 0.650514 0.75944 40 | 39 5.59351 6.14177 0.0690859 -0.00832853 0.00433246 0.66661 0.745348 41 | 40 5.60972 6.60536 0.0612215 -0.00845164 0.00287174 0.68079 0.732424 42 | 41 5.61861 7.07193 0.0587561 -0.00747551 0.00204118 0.693463 0.720451 43 | 42 5.61105 7.534 0.0598398 -0.00644758 0.00135963 0.704689 0.709486 44 | 43 5.58465 8.02347 0.0555732 -0.00597267 0.00033841 0.714193 0.699923 45 | 44 5.55683 8.52989 0.0496001 -0.00549909 -0.000738754 0.721535 0.692356 46 | 45 5.51085 9.06657 0.0409439 -0.00521435 -0.00130887 0.727334 0.686263 47 | 46 5.46902 9.61408 0.0435741 -0.00513382 -0.000974947 0.731671 0.681638 48 | 47 5.4157 10.1597 0.0412557 -0.00568428 -0.000645345 0.735015 0.678027 49 | 48 5.35854 10.74 0.0461785 -0.00652756 -0.000663423 0.737327 0.675504 50 | 49 5.2951 11.3274 0.0422662 -0.00684723 -0.000154238 0.73884 0.673847 51 | 50 5.23572 11.9307 0.0394771 -0.00684689 0.000358469 0.739414 0.673216 52 | 51 5.17959 12.5512 0.0369263 -0.00715353 0.0013501 0.739207 0.673439 53 | 52 5.1212 13.2017 0.0334131 -0.00765628 0.00232308 0.738687 0.674001 54 | 53 5.05761 13.8504 0.0270114 -0.00801582 0.00203 0.738098 0.674642 55 | 54 4.98891 14.5128 0.0308112 -0.00825443 0.000506954 0.737503 0.675293 56 | 55 4.92933 15.1993 0.0199832 -0.00835971 0.000262357 0.737016 0.675824 57 | 56 4.8684 15.8929 0.0131471 -0.0089422 0.00149417 0.736399 0.676487 58 | 57 4.79735 16.617 0.00486584 -0.0102374 0.00246625 0.735824 0.677091 59 | 58 4.73689 17.3439 -0.00221012 -0.0109838 0.00324714 0.735118 0.677843 60 | 59 4.67081 18.0929 -0.00744534 -0.0118656 0.00208332 0.734482 0.678521 61 | 60 4.60624 18.8457 -0.0126498 -0.0120207 0.000325866 0.733871 0.679182 62 | 61 4.53879 19.6085 -0.0194351 -0.0119115 -4.32956e-05 0.733391 0.679703 63 | 62 4.48514 20.3896 -0.0373071 -0.0117278 0.00138278 0.732939 0.680192 64 | 63 4.42868 21.1772 -0.0424002 -0.0120189 0.00251197 0.732427 0.680735 65 | 64 4.3682 21.9765 -0.0559773 -0.0118878 0.00340898 0.732093 0.681093 66 | 65 4.3015 22.781 -0.0583463 -0.0101289 0.00250393 0.731857 0.681379 67 | 66 4.23928 23.586 -0.060558 -0.00823739 -0.000274333 0.73179 0.68148 68 | 67 4.18853 24.406 -0.0692581 -0.00684292 -0.00219167 0.731881 0.681395 69 | 68 4.1267 25.227 -0.0652381 -0.00616307 -0.000981653 0.732062 0.681209 70 | 69 4.06192 26.0679 -0.0702312 -0.00760207 0.00255061 0.731998 0.68126 71 | 70 3.99518 26.93 -0.0763381 -0.0106898 0.00419494 0.731982 0.681227 72 | 71 3.91599 27.7735 -0.0846521 -0.0123434 0.00601597 0.732161 0.680993 73 | 72 3.8481 28.618 -0.0904841 -0.0135162 0.00542183 0.732166 0.68097 74 | 73 3.78629 29.4591 -0.0997501 -0.0130061 0.0040068 0.732278 0.680869 75 | 74 3.72104 30.2971 -0.102668 -0.0130031 0.00236486 0.732527 0.680609 76 | 75 3.65679 31.1409 -0.117535 -0.0133158 0.00254744 0.732642 0.680479 77 | 76 3.58172 31.9833 -0.126961 -0.0141285 0.00299756 0.732516 0.680597 78 | 77 3.51789 32.8151 -0.131373 -0.0137145 0.00281508 0.732473 0.680652 79 | 78 3.45125 33.6434 -0.135644 -0.0130831 0.000155666 0.732208 0.680955 80 | 79 3.38263 34.4715 -0.138799 -0.0121377 -0.00143488 0.732261 0.680915 81 | 80 3.31628 35.2989 -0.145918 -0.0120163 -0.00127969 0.732088 0.681103 82 | 81 3.25146 36.1263 -0.146435 -0.0122474 0.000309995 0.7318 0.68141 83 | 82 3.18628 36.9683 -0.154842 -0.0141132 0.00176419 0.731707 0.681471 84 | 83 3.13543 37.8028 -0.168053 -0.0148419 0.00460037 0.731592 0.681566 85 | 84 3.06453 38.6361 -0.174519 -0.0161939 0.00576426 0.73153 0.681592 86 | 85 3.0039 39.4694 -0.18531 -0.0164148 0.00558283 0.731397 0.681731 87 | 86 2.94582 40.2852 -0.192878 -0.0151926 0.00420654 0.731348 0.681822 88 | 87 2.87417 41.1163 -0.201489 -0.0143106 0.00204995 0.731255 0.681951 89 | 88 2.80574 41.9542 -0.211265 -0.0145812 -0.000168115 0.731187 0.682021 90 | 89 2.74426 42.7787 -0.224109 -0.0147658 -0.0016916 0.731311 0.681883 91 | 90 2.68123 43.6063 -0.226137 -0.0134167 -0.00196168 0.731587 0.681613 92 | 91 2.62079 44.4306 -0.226449 -0.0113691 -0.00216514 0.732032 0.681172 93 | 92 2.56574 45.2493 -0.223936 -0.0092318 -0.000940536 0.732396 0.680815 94 | 93 2.49875 46.0728 -0.222974 -0.0097264 0.000701955 0.732991 0.680168 95 | 94 2.43454 46.9013 -0.229098 -0.0106714 0.00360911 0.733652 0.679432 96 | 95 2.37326 47.7177 -0.238863 -0.0114233 0.00541144 0.734228 0.678786 97 | 96 2.30893 48.5288 -0.240795 -0.0119684 0.00443016 0.734773 0.678193 98 | 97 2.23615 49.3257 -0.239619 -0.0115005 0.00244139 0.735247 0.677698 99 | 98 2.15579 50.1267 -0.23614 -0.0111179 0.000652795 0.735646 0.677275 100 | 99 2.07789 50.9219 -0.240652 -0.011249 -0.000184182 0.735981 0.676909 101 | 100 1.99961 51.7172 -0.24658 -0.0128761 -0.00125756 0.736278 0.676556 102 | 101 1.92287 52.5097 -0.247362 -0.0134414 -0.000873177 0.736594 0.676201 103 | 102 1.85091 53.2953 -0.246337 -0.0136666 -0.00133781 0.737056 0.675693 104 | 103 1.77583 54.0826 -0.248587 -0.0142241 -0.00171734 0.73709 0.675643 105 | 104 1.70545 54.8531 -0.254345 -0.0142405 -0.000597402 0.737272 0.675446 106 | 105 1.62902 55.6392 -0.256965 -0.0149661 0.000405855 0.737441 0.675245 107 | 106 1.56458 56.4137 -0.270928 -0.0161364 0.00189685 0.737217 0.675461 108 | 107 1.48155 57.1944 -0.271623 -0.0172477 0.00264377 0.737407 0.675223 109 | 108 1.41611 57.9453 -0.276565 -0.0169805 0.00315392 0.737609 0.675007 110 | 109 1.34519 58.6855 -0.282108 -0.015994 0.00291609 0.73768 0.674954 111 | 110 1.28088 59.4213 -0.292153 -0.0150197 0.00142862 0.737946 0.674691 112 | 111 1.21226 60.136 -0.299162 -0.0146667 -0.000262057 0.737977 0.674666 113 | 112 1.14103 60.8386 -0.300715 -0.0133431 -0.000467273 0.737512 0.675202 114 | 113 1.07311 61.5386 -0.300434 -0.0135897 -0.0012093 0.736604 0.676187 115 | 114 1.01478 62.2123 -0.303292 -0.0141273 -0.00106354 0.735323 0.677569 116 | 115 0.968863 62.8737 -0.30138 -0.0145156 -0.000290159 0.73338 0.679663 117 | 116 0.911716 63.5226 -0.306298 -0.0147716 0.000268866 0.730949 0.682273 118 | 117 0.867249 64.1601 -0.307516 -0.0158616 9.71163e-05 0.727825 0.68558 119 | 118 0.835792 64.7885 -0.310595 -0.0172064 -1.76261e-05 0.72366 0.689942 120 | 119 0.811021 65.3868 -0.315335 -0.0186912 -0.00046138 0.718601 0.695171 121 | 120 0.802279 65.9655 -0.323977 -0.0196619 -0.000705034 0.712222 0.701679 122 | 121 0.807861 66.5349 -0.327905 -0.0198554 -0.000359977 0.704442 0.709483 123 | 122 0.823664 67.0684 -0.331042 -0.0195066 0.000306499 0.69535 0.718406 124 | 123 0.871803 67.584 -0.333474 -0.0191767 0.000455711 0.684944 0.728343 125 | 124 0.930376 68.0895 -0.33851 -0.0186286 0.000900589 0.672463 0.739895 126 | 125 1.01219 68.5714 -0.344921 -0.0183508 0.00139628 0.658314 0.752518 127 | 126 1.11124 69.0206 -0.342886 -0.0176228 0.0019818 0.643024 0.76564 128 | 127 1.22058 69.4722 -0.349302 -0.017286 0.00289635 0.62518 0.780284 129 | 128 1.37922 69.9013 -0.357475 -0.0154564 0.0040915 0.606223 0.795134 130 | 129 1.53761 70.319 -0.348413 -0.0115877 0.00590271 0.585153 0.810818 131 | 130 1.74457 70.7192 -0.345804 -0.00840604 0.00631459 0.56337 0.826138 132 | 131 1.94082 71.1025 -0.342985 -0.00535202 0.00731609 0.539874 0.841697 133 | 132 2.19263 71.4803 -0.352895 -0.00488311 0.00778864 0.516245 0.856391 134 | 133 2.42254 71.8449 -0.368141 -0.00390825 0.0083556 0.492428 0.870304 135 | 134 2.68135 72.1918 -0.375439 -0.000897196 0.0108682 0.468959 0.883153 136 | 135 3.00343 72.5176 -0.357803 0.00402936 0.0142792 0.445265 0.895276 137 | 136 3.28101 72.8163 -0.35642 0.00560024 0.0136135 0.420961 0.906959 138 | 137 3.59732 73.1064 -0.373394 0.00608028 0.00984814 0.395964 0.918193 139 | 138 3.89643 73.388 -0.367413 0.00641486 0.00458815 0.369637 0.929143 140 | 139 4.26824 73.6622 -0.370499 0.00605797 -0.000118477 0.342425 0.939526 141 | 140 4.63415 73.9254 -0.376973 0.00574639 -0.00179519 0.314401 0.949271 142 | 141 5.04016 74.1739 -0.374362 0.00606951 -0.00262152 0.286084 0.958182 143 | 142 5.50908 74.4167 -0.379311 0.00512586 -0.00398071 0.258264 0.966053 144 | 143 5.96203 74.6418 -0.361195 0.00421205 -0.00317164 0.231765 0.972758 145 | 144 6.46116 74.8643 -0.361321 0.00170601 -0.00334518 0.207477 0.978233 146 | 145 6.95589 75.062 -0.357726 -0.00101781 -0.00440533 0.18536 0.98266 147 | 146 7.49764 75.2497 -0.3572 -0.00322283 -0.00406201 0.166057 0.986103 148 | 147 8.06568 75.4243 -0.35024 -0.00372987 -0.0029447 0.149929 0.988685 149 | 148 8.62699 75.5824 -0.338822 -0.00312949 -0.00184669 0.137183 0.990539 150 | 149 9.23191 75.7277 -0.330051 -0.00297234 -0.000735357 0.126343 0.991982 151 | 150 9.84058 75.8632 -0.329991 -0.00360478 0.00067101 0.117085 0.993115 152 | 151 10.477 76.0117 -0.325854 -0.00567212 0.00132866 0.109215 0.994001 153 | 152 11.1223 76.1533 -0.335048 -0.00692292 0.00168605 0.102434 0.994714 154 | 153 11.7734 76.291 -0.322494 -0.00682361 0.00191107 0.0956034 0.995394 155 | 154 12.4462 76.4008 -0.321888 -0.00712905 0.00187036 0.0889337 0.99601 156 | 155 13.1447 76.5187 -0.319176 -0.00725121 0.00219562 0.081626 0.996634 157 | 156 13.8603 76.6248 -0.322096 -0.0082032 0.00256696 0.0744761 0.997186 158 | 157 14.5771 76.7345 -0.314972 -0.00772396 0.00133067 0.0675242 0.997687 159 | 158 15.2975 76.8296 -0.310591 -0.00823042 -0.00112749 0.0621591 0.998032 160 | 159 16.0409 76.9114 -0.298623 -0.00827954 -0.00400254 0.0572356 0.998318 161 | 160 16.8035 77.0037 -0.294899 -0.00700108 -0.00415313 0.053006 0.998561 162 | 161 17.5724 77.0777 -0.283966 -0.00789199 -0.0013265 0.049833 0.998726 163 | 162 18.3375 77.1518 -0.288269 -0.00970841 0.00259502 0.0475107 0.99882 164 | 163 19.1265 77.2309 -0.27823 -0.010603 0.00455127 0.0452046 0.998911 165 | 164 19.8933 77.3088 -0.264314 -0.010119 0.00433561 0.043393 0.998997 166 | 165 20.6557 77.3808 -0.260369 -0.00983654 0.0038227 0.0418126 0.99907 167 | 166 21.4343 77.433 -0.266502 -0.00965637 0.00493945 0.0406727 0.999114 168 | 167 22.2077 77.4961 -0.259658 -0.00854727 0.00626799 0.0395608 0.999161 169 | 168 22.9775 77.5476 -0.258622 -0.00629853 0.00719185 0.038046 0.99923 170 | 169 23.733 77.6113 -0.25015 -0.00615132 0.00576057 0.0365294 0.999297 171 | 170 24.483 77.6811 -0.248016 -0.00846127 0.00195037 0.0354624 0.999333 172 | 171 25.2432 77.739 -0.240083 -0.00855844 -0.00171047 0.0346174 0.999363 173 | 172 25.9983 77.801 -0.228333 -0.0089798 -0.00374053 0.0340798 0.999372 174 | 173 26.7721 77.8508 -0.222085 -0.00958752 -0.0031266 0.0332224 0.999397 175 | 174 27.5247 77.9077 -0.205614 -0.0114237 -0.00117072 0.0320855 0.999419 176 | 175 28.2909 77.9622 -0.200921 -0.0124813 0.00110132 0.0312261 0.999434 177 | 176 29.0464 78.0084 -0.18123 -0.012338 0.00223757 0.0300455 0.99947 178 | 177 29.8045 78.0631 -0.174858 -0.010657 0.00238833 0.0293324 0.99951 179 | 178 30.5626 78.1176 -0.165153 -0.00994861 0.00228859 0.0286103 0.999539 180 | 179 31.3185 78.1647 -0.157035 -0.0101315 0.00167978 0.0280793 0.999553 181 | 180 32.0676 78.2057 -0.153112 -0.00920006 0.000946504 0.0278059 0.999571 182 | 181 32.83 78.2349 -0.14414 -0.00896904 0.00110107 0.0273122 0.999586 183 | 182 33.5934 78.279 -0.144478 -0.00940926 0.00140901 0.0270078 0.99959 184 | 183 34.3732 78.3298 -0.134385 -0.00993634 0.00108387 0.0268636 0.999589 185 | 184 35.1487 78.3827 -0.130143 -0.00993903 0.000881486 0.0274774 0.999573 186 | 185 35.9401 78.4284 -0.115455 -0.00936829 0.00114387 0.0286695 0.999544 187 | 186 36.728 78.4773 -0.112626 -0.00957219 0.00117196 0.0300393 0.999502 188 | 187 37.5265 78.5345 -0.105698 -0.0111747 0.000837369 0.031669 0.999436 189 | 188 38.3162 78.5931 -0.0960349 -0.0118795 -0.00133122 0.0328897 0.999387 190 | 189 39.118 78.6606 -0.0852189 -0.0119112 -0.0031711 0.0339314 0.999348 191 | 190 39.9444 78.7235 -0.0755178 -0.0117963 -0.00369073 0.0349496 0.999313 192 | 191 40.7653 78.7854 -0.0630146 -0.0115545 -0.00322258 0.0360735 0.999277 193 | 192 41.5833 78.8435 -0.0494954 -0.0112572 -0.0026746 0.0373146 0.999237 194 | 193 42.4215 78.9022 -0.0286674 -0.0112102 -0.00199813 0.0381427 0.999207 195 | 194 43.2661 78.9735 -0.0310504 -0.0108872 -0.00029689 0.0386749 0.999192 196 | 195 44.1121 79.0474 -0.0216994 -0.0104914 0.00194082 0.0391215 0.999177 197 | 196 44.9651 79.1228 -0.0150718 -0.0100397 0.00320595 0.0388455 0.99919 198 | 197 45.8372 79.1893 -0.00842536 -0.0115141 0.00328629 0.0378783 0.999211 199 | 198 46.6928 79.2611 -0.00409214 -0.0119893 0.00288652 0.0370493 0.999237 200 | 199 47.5688 79.3217 -0.000912213 -0.0106832 0.00186028 0.0360143 0.999292 201 | 200 48.4429 79.3938 0.010351 -0.00870049 0.00118114 0.0352093 0.999341 202 | 201 49.3216 79.4551 0.0141272 -0.00768642 0.00119877 0.0342593 0.999383 203 | 202 50.2005 79.5131 0.0182608 -0.00691264 0.00231395 0.0336 0.999409 204 | 203 51.0733 79.5694 0.0293142 -0.00537626 0.00347216 0.0333377 0.999424 205 | 204 51.9492 79.6286 0.0367324 -0.00496638 0.00370481 0.03294 0.999438 206 | 205 52.8169 79.6935 0.0439193 -0.00591994 0.00235531 0.0325421 0.99945 207 | 206 53.679 79.7654 0.0616316 -0.00861078 -0.000389274 0.032082 0.999448 208 | 207 54.5432 79.8292 0.0697105 -0.0089282 -0.00309097 0.0314256 0.999461 209 | 208 55.3968 79.9007 0.0930131 -0.0123384 -0.00623276 0.0309563 0.999425 210 | 209 56.2535 79.9591 0.111346 -0.0121694 -0.00687456 0.0306034 0.999434 211 | 210 57.1171 80.0124 0.126684 -0.0106885 -0.00367678 0.0302787 0.999478 212 | 211 57.9787 80.0722 0.143027 -0.00850604 0.000740551 0.0306393 0.999494 213 | 212 58.8312 80.1241 0.135861 -0.00639283 0.00392365 0.0311817 0.999486 214 | 213 59.6526 80.1783 0.168502 -0.00833901 0.0035057 0.0322647 0.999438 215 | 214 60.497 80.2245 0.188735 -0.00613072 0.00220962 0.0333989 0.999421 216 | 215 61.3329 80.2839 0.188322 -0.00503061 0.00122346 0.0346766 0.999385 217 | 216 62.1603 80.3518 0.20472 -0.00551823 0.000128612 0.0361886 0.99933 218 | 217 62.975 80.4229 0.215785 -0.00639262 -0.00152664 0.0377133 0.999267 219 | 218 63.803 80.496 0.226071 -0.00716891 -0.00325852 0.0398245 0.999176 220 | 219 64.6231 80.5669 0.253467 -0.00813548 -0.00502808 0.0415755 0.99909 221 | 220 65.4358 80.6534 0.259321 -0.0103559 -0.0054801 0.0432229 0.998997 222 | 221 66.241 80.7351 0.286238 -0.0121751 -0.00461951 0.0446884 0.998916 223 | 222 67.0458 80.8237 0.299242 -0.0135911 -0.00213826 0.0464841 0.998824 224 | 223 67.8494 80.9049 0.314644 -0.0127868 0.000895751 0.0484483 0.998743 225 | 224 68.6423 80.9912 0.323368 -0.0121991 0.00262031 0.0506342 0.998639 226 | 225 69.4247 81.0889 0.338628 -0.012204 0.00324562 0.0538239 0.998471 227 | 226 70.217 81.1753 0.342372 -0.0112914 0.00448512 0.0571666 0.998291 228 | 227 70.9853 81.273 0.349911 -0.01215 0.00473621 0.0603208 0.998094 229 | 228 71.754 81.3825 0.355211 -0.0142052 0.00422866 0.0633562 0.997881 230 | 229 72.5229 81.4923 0.363802 -0.0163146 0.00250459 0.0663787 0.997658 231 | 230 73.2964 81.605 0.364461 -0.0155331 0.000900554 0.0692605 0.997477 232 | 231 74.0588 81.7201 0.375827 -0.0161188 0.000290968 0.071946 0.997278 233 | 232 74.8317 81.8459 0.372971 -0.0160909 0.00224091 0.0746067 0.997081 234 | 233 75.5967 81.98 0.384582 -0.0158637 0.004689 0.0774939 0.996856 235 | 234 76.357 82.1089 0.390454 -0.014495 0.0059397 0.0806774 0.996617 236 | 235 77.1045 82.2399 0.3935 -0.0148511 0.00404128 0.0840841 0.99634 237 | 236 77.8482 82.3778 0.402097 -0.0148782 0.000344752 0.0883514 0.995978 238 | 237 78.5846 82.5152 0.404303 -0.013426 -0.000806116 0.0931072 0.995565 239 | 238 79.3259 82.6684 0.414189 -0.0129565 0.000676378 0.0985832 0.995044 240 | 239 80.0556 82.8343 0.41378 -0.0132435 0.00328497 0.104215 0.994461 241 | 240 80.7907 83.0024 0.411629 -0.0136052 0.00706542 0.110164 0.993795 242 | 241 81.5309 83.1783 0.423794 -0.012556 0.00922439 0.11599 0.993128 243 | 242 82.2409 83.3725 0.424698 -0.0137036 0.00708392 0.122006 0.99241 244 | 243 82.957 83.5679 0.431863 -0.0154209 0.00200175 0.127868 0.991669 245 | 244 83.6777 83.7684 0.431807 -0.0143359 -0.000595351 0.134248 0.990844 246 | 245 84.3917 83.9794 0.419468 -0.0140542 0.00131188 0.140564 0.989971 247 | 246 85.1125 84.2023 0.431399 -0.0142729 0.00506661 0.146551 0.989087 248 | 247 85.8388 84.4408 0.433309 -0.014192 0.00795688 0.152847 0.988116 249 | 248 86.5445 84.6732 0.4395 -0.0117422 0.00760186 0.159527 0.987094 250 | 249 87.2449 84.9218 0.423704 -0.0109916 0.00524194 0.165397 0.986152 251 | 250 87.9473 85.1703 0.433674 -0.0100236 0.00192122 0.170149 0.985366 252 | 251 88.664 85.4223 0.432848 -0.00902605 -0.00107192 0.174141 0.984679 253 | 252 89.3699 85.6987 0.441383 -0.00942071 -0.00214807 0.177919 0.983998 254 | 253 90.059 85.9743 0.441513 -0.0110968 -0.00262258 0.181915 0.983248 255 | 254 90.7642 86.2553 0.453841 -0.0118207 -0.00170889 0.186027 0.982472 256 | 255 91.4582 86.5396 0.453506 -0.0108987 0.00142755 0.19006 0.981711 257 | 256 92.1772 86.8295 0.45855 -0.0106595 0.00558766 0.193791 0.980969 258 | 257 92.8933 87.1499 0.453128 -0.0132134 0.00874955 0.196807 0.980314 259 | 258 93.5872 87.4684 0.459075 -0.0161571 0.00728167 0.199677 0.979702 260 | 259 94.2699 87.7759 0.456117 -0.0175797 0.00276288 0.202799 0.979059 261 | 260 94.9572 88.0762 0.465619 -0.015173 -0.00066396 0.205385 0.978563 262 | 261 95.6547 88.388 0.461663 -0.0157875 -0.00134496 0.207515 0.978104 263 | 262 96.359 88.7186 0.455984 -0.017479 0.000708924 0.209819 0.977584 264 | 263 97.0604 89.0539 0.461183 -0.0173392 0.00316029 0.212412 0.977021 265 | 264 97.7591 89.3806 0.474762 -0.0162472 0.00279336 0.215536 0.976357 266 | 265 98.4602 89.7079 0.477549 -0.0162281 -0.000487977 0.218011 0.975811 267 | 266 99.1523 90.0472 0.483217 -0.0166595 -0.00413175 0.220502 0.975236 268 | 267 99.8503 90.4007 0.485438 -0.0174262 -0.00528249 0.223257 0.97459 269 | 268 100.552 90.7527 0.491801 -0.0176727 -0.00327348 0.225411 0.974098 270 | 269 101.249 91.1073 0.504582 -0.0177661 -0.0019211 0.22749 0.973617 271 | 270 101.937 91.4628 0.518146 -0.0186184 -0.00186749 0.230109 0.972985 272 | 271 102.616 91.8078 0.524377 -0.0179374 -0.00210103 0.23257 0.972412 273 | 272 103.293 92.162 0.537668 -0.0170435 -0.00228389 0.235015 0.97184 274 | 273 103.968 92.5118 0.543265 -0.0165761 -0.00181831 0.237236 0.971309 275 | 274 104.63 92.8753 0.552801 -0.0174331 -0.00185994 0.239537 0.970729 276 | 275 105.297 93.2324 0.557913 -0.0169694 -0.00170211 0.241863 0.97016 277 | 276 105.964 93.5923 0.572839 -0.0165432 -0.00350718 0.244509 0.969499 278 | 277 106.613 93.9558 0.582988 -0.0153349 -0.00547248 0.246579 0.968986 279 | 278 107.258 94.3099 0.597149 -0.0153155 -0.00692777 0.248513 0.968483 280 | 279 107.902 94.6856 0.603246 -0.0159936 -0.0056216 0.250791 0.967893 281 | 280 108.542 95.0452 0.61078 -0.0162103 -0.00117787 0.252415 0.967483 282 | 281 109.177 95.3948 0.614927 -0.0151607 0.0037372 0.253651 0.96717 283 | 282 109.807 95.7585 0.621153 -0.013325 0.00697734 0.255524 0.966686 284 | 283 110.415 96.1132 0.626423 -0.011745 0.00735896 0.257134 0.966276 285 | 284 111.012 96.4612 0.632131 -0.0119762 0.00547119 0.259009 0.965785 286 | 285 111.594 96.8053 0.631442 -0.0117779 0.00396556 0.260575 0.965374 287 | 286 112.149 97.1488 0.636944 -0.0117931 0.00324193 0.262025 0.964983 288 | 287 112.712 97.4643 0.641366 -0.0109157 0.00327674 0.263242 0.964662 289 | 288 113.228 97.7915 0.646844 -0.0111628 0.00373779 0.264506 0.964312 290 | 289 113.732 98.0954 0.648201 -0.0101534 0.00475722 0.265877 0.963942 291 | 290 114.213 98.3886 0.652203 -0.00948883 0.00523861 0.267144 0.963596 292 | 291 114.671 98.6683 0.657789 -0.00840689 0.0056993 0.268347 0.963269 293 | 292 115.127 98.9287 0.666073 -0.00854769 0.00513636 0.269259 0.963016 294 | 293 115.541 99.1871 0.669396 -0.00890434 0.00338373 0.270242 0.962745 295 | 294 115.934 99.4364 0.674213 -0.00825688 0.00151448 0.271451 0.962416 296 | 295 116.313 99.6742 0.681459 -0.0070406 0.000636585 0.273594 0.961819 297 | 296 116.687 99.9003 0.685486 -0.00463908 0.00147359 0.276061 0.961128 298 | 297 117.045 100.135 0.687343 -0.00464691 0.00214952 0.279106 0.960247 299 | 298 117.375 100.367 0.692582 -0.00628379 0.00258075 0.282221 0.959325 300 | 299 117.689 100.594 0.694751 -0.00918657 0.00393018 0.285659 0.958279 301 | 300 117.985 100.798 0.691886 -0.0110266 0.00658503 0.288809 0.957301 302 | 301 118.269 100.983 0.700009 -0.0115883 0.00879757 0.292551 0.956139 303 | 302 118.532 101.162 0.699619 -0.00950542 0.0101099 0.29693 0.954798 304 | 303 118.785 101.33 0.705102 -0.00815836 0.0108448 0.302099 0.95318 305 | 304 119.014 101.496 0.708254 -0.00698706 0.0117382 0.308854 0.951012 306 | 305 119.217 101.674 0.708608 -0.00697996 0.0122295 0.316595 0.948456 307 | 306 119.401 101.85 0.708356 -0.00779169 0.0117185 0.325632 0.945392 308 | 307 119.582 102.019 0.716557 -0.00768805 0.0107215 0.335904 0.941804 309 | 308 119.748 102.179 0.714429 -0.00741105 0.00830366 0.346468 0.937996 310 | 309 119.891 102.327 0.718261 -0.00640235 0.005507 0.357018 0.934059 311 | 310 120.027 102.481 0.712385 -0.0072062 0.00286575 0.367072 0.93016 312 | 311 120.156 102.639 0.702923 -0.00995497 0.000572373 0.377095 0.926121 313 | 312 120.287 102.79 0.69103 -0.0113128 -0.000123892 0.387696 0.921718 314 | 313 120.42 102.966 0.701661 -0.010284 0.00080096 0.399458 0.916693 315 | 314 120.554 103.138 0.699322 -0.00930185 0.00181168 0.411321 0.911441 316 | 315 120.682 103.304 0.706026 -0.00971365 0.00283816 0.42397 0.90562 317 | 316 120.8 103.487 0.690133 -0.0116919 0.00328064 0.437394 0.899188 318 | 317 120.91 103.673 0.692918 -0.0135753 0.00431702 0.450735 0.892544 319 | 318 121.008 103.871 0.692832 -0.0148493 0.00490913 0.464381 0.885497 320 | 319 121.109 104.059 0.695568 -0.0167775 0.0048225 0.477721 0.878338 321 | 320 121.193 104.244 0.688153 -0.0191679 0.00486117 0.490882 0.871002 322 | 321 121.268 104.449 0.685517 -0.0207736 0.00520445 0.504558 0.863112 323 | 322 121.345 104.652 0.696639 -0.0206613 0.0054018 0.518794 0.854633 324 | 323 121.419 104.845 0.7002 -0.0198949 0.0041757 0.533539 0.845531 325 | 324 121.485 105.08 0.691064 -0.0186032 0.002326 0.549235 0.835458 326 | 325 121.555 105.313 0.687486 -0.0178553 0.00114689 0.566021 0.824197 327 | 326 121.622 105.593 0.680532 -0.0175843 0.00118498 0.583789 0.811714 328 | 327 121.685 105.888 0.670666 -0.0168219 0.000801641 0.602025 0.7983 329 | 328 121.731 106.181 0.664247 -0.0157938 -5.57761e-05 0.620668 0.783914 330 | 329 121.758 106.512 0.655769 -0.0149615 -0.000467589 0.640011 0.76822 331 | 330 121.776 106.863 0.645943 -0.0146289 -0.000404078 0.659275 0.75176 332 | 331 121.78 107.193 0.635043 -0.0147273 0.000427842 0.678337 0.734603 333 | 332 121.767 107.56 0.628207 -0.0144799 0.00247459 0.697633 0.716305 334 | 333 121.737 107.918 0.6285 -0.0139941 0.00451284 0.716336 0.6976 335 | 334 121.685 108.314 0.619518 -0.0132201 0.00631108 0.734929 0.677986 336 | 335 121.614 108.713 0.617397 -0.0129069 0.00783187 0.752818 0.658056 337 | 336 121.515 109.107 0.603633 -0.0125271 0.00892085 0.769582 0.638363 338 | 337 121.383 109.541 0.590842 -0.0118475 0.0102018 0.785763 0.61833 339 | 338 121.244 109.974 0.580297 -0.0106517 0.0118918 0.801113 0.5983 340 | 339 121.084 110.391 0.574289 -0.00940894 0.0135118 0.815461 0.578577 341 | 340 120.881 110.85 0.562087 -0.0081989 0.0153201 0.829188 0.5587 342 | 341 120.671 111.288 0.548065 -0.00713885 0.0165633 0.841722 0.53961 343 | 342 120.419 111.758 0.537288 -0.00653039 0.0172798 0.853334 0.521037 344 | 343 120.138 112.232 0.520262 -0.00626709 0.0173643 0.863512 0.503989 345 | 344 119.849 112.708 0.508846 -0.00629773 0.0170898 0.871942 0.48927 346 | 345 119.53 113.209 0.492097 -0.00642582 0.0160149 0.878741 0.476987 347 | 346 119.191 113.716 0.483373 -0.00648187 0.0151114 0.884063 0.467078 348 | 347 118.82 114.225 0.46668 -0.00664325 0.0146335 0.888162 0.45925 349 | 348 118.44 114.727 0.454928 -0.00665908 0.015108 0.891226 0.453259 350 | 349 118.024 115.244 0.440487 -0.00671574 0.0156057 0.893684 0.448376 351 | 350 117.597 115.766 0.430142 -0.00683779 0.0164146 0.895828 0.444044 352 | 351 117.162 116.311 0.415685 -0.00710011 0.0165246 0.897642 0.440359 353 | 352 116.727 116.865 0.401651 -0.00741794 0.0162479 0.899173 0.437228 354 | 353 116.27 117.436 0.385259 -0.0076396 0.0161062 0.900441 0.434612 355 | 354 115.797 118.022 0.368889 -0.00761817 0.0166573 0.901401 0.432597 356 | 355 115.318 118.613 0.354391 -0.00757146 0.0171711 0.902013 0.4313 357 | 356 114.833 119.214 0.334955 -0.00745482 0.0176584 0.90227 0.430745 358 | 357 114.33 119.823 0.321189 -0.00731176 0.0173259 0.902483 0.430314 359 | 358 113.818 120.436 0.301742 -0.00688578 0.0172496 0.9027 0.429869 360 | 359 113.288 121.074 0.288299 -0.00639626 0.0173763 0.902891 0.429471 361 | 360 112.75 121.735 0.268438 -0.00681306 0.0173284 0.903018 0.429199 362 | 361 112.195 122.403 0.248253 -0.00790502 0.0173186 0.903196 0.428806 363 | 362 111.652 123.063 0.23169 -0.00866176 0.018136 0.903416 0.428293 364 | 363 111.093 123.74 0.216577 -0.00843486 0.018603 0.903676 0.427729 365 | 364 110.519 124.433 0.201952 -0.00770896 0.0184022 0.903854 0.427376 366 | 365 109.939 125.135 0.181254 -0.0069752 0.0181821 0.90397 0.427152 367 | 366 109.367 125.833 0.162414 -0.00642517 0.0191373 0.904107 0.426829 368 | 367 108.771 126.548 0.149459 -0.00553825 0.0202041 0.904319 0.426343 369 | 368 108.17 127.275 0.12661 -0.00440849 0.0198437 0.904561 0.42586 370 | 369 107.566 128.003 0.114955 -0.00263191 0.0186844 0.904885 0.425237 371 | 370 106.939 128.74 0.105978 -0.00163634 0.017148 0.905114 0.42482 372 | 371 106.318 129.483 0.0946764 -0.00159274 0.0159655 0.905117 0.42486 373 | 372 105.678 130.235 0.0839389 -0.00271222 0.0154868 0.905061 0.424991 374 | 373 105.033 130.998 0.0729512 -0.00392088 0.0160473 0.905024 0.42504 375 | 374 104.4 131.752 0.0640942 -0.00490474 0.0169636 0.905088 0.424857 376 | 375 103.762 132.519 0.0539023 -0.00554379 0.0178404 0.905186 0.424605 377 | 376 103.123 133.279 0.0426219 -0.00595265 0.0181355 0.905242 0.424467 378 | 377 102.485 134.04 0.0326627 -0.00610124 0.018512 0.90523 0.424475 379 | 378 101.835 134.802 0.0204727 -0.00645338 0.0182344 0.905312 0.424307 380 | 379 101.194 135.559 0.00895255 -0.00692113 0.0182591 0.905337 0.424245 381 | 380 100.561 136.322 -0.00566141 -0.00762614 0.0185744 0.9054 0.424085 382 | 381 99.9238 137.084 -0.0260167 -0.00805108 0.0188348 0.905475 0.423904 383 | 382 99.2938 137.84 -0.0373794 -0.00809559 0.0186227 0.905578 0.423694 384 | 383 98.6459 138.609 -0.051968 -0.00758436 0.0187773 0.905768 0.42329 385 | 384 98.0058 139.354 -0.063192 -0.00751895 0.0183529 0.906086 0.422629 386 | 385 97.3791 140.107 -0.0798361 -0.007142 0.0191837 0.9063 0.422139 387 | 386 96.7324 140.865 -0.0910565 -0.00695399 0.0190772 0.906477 0.421767 388 | 387 96.103 141.606 -0.0997533 -0.00661815 0.018905 0.906684 0.421336 389 | 388 95.4578 142.365 -0.115968 -0.00653828 0.018397 0.906796 0.421116 390 | 389 94.8275 143.102 -0.128478 -0.00669564 0.0179262 0.906894 0.420925 391 | 390 94.175 143.861 -0.140081 -0.0076579 0.016378 0.906963 0.420822 392 | 391 93.5364 144.615 -0.152229 -0.00774029 0.0157421 0.906766 0.421269 393 | 392 92.9008 145.358 -0.170673 -0.00774381 0.0148272 0.906602 0.421656 394 | 393 92.2593 146.104 -0.177464 -0.00719744 0.0141467 0.906183 0.422589 395 | 394 91.6328 146.843 -0.191042 -0.00736285 0.0143006 0.90584 0.423315 396 | 395 91.0076 147.595 -0.199776 -0.00777825 0.0155523 0.90546 0.424076 397 | 396 90.3761 148.355 -0.218686 -0.00963656 0.0173836 0.90518 0.424564 398 | 397 89.7426 149.114 -0.237156 -0.0117065 0.0201043 0.904909 0.424969 399 | 398 89.1108 149.878 -0.257435 -0.0124325 0.0209464 0.904774 0.425195 400 | 399 88.4838 150.627 -0.276702 -0.0108635 0.0200169 0.904743 0.425349 401 | 400 87.8626 151.375 -0.300744 -0.00896407 0.0185106 0.90472 0.425509 402 | 401 87.233 152.128 -0.319412 -0.00877233 0.0187358 0.904715 0.425516 403 | 402 86.6044 152.883 -0.341723 -0.0100744 0.0192235 0.904739 0.425414 404 | 403 85.9667 153.644 -0.358799 -0.010522 0.0199329 0.904806 0.425227 405 | 404 85.3474 154.387 -0.376509 -0.00984171 0.0200449 0.90494 0.424952 406 | 405 84.7212 155.135 -0.391121 -0.00914408 0.0197978 0.905077 0.424687 407 | 406 84.1048 155.869 -0.411993 -0.0095908 0.020071 0.905228 0.424343 408 | 407 83.4846 156.607 -0.433986 -0.011178 0.0209443 0.90538 0.423938 409 | 408 82.8608 157.35 -0.452325 -0.0122205 0.0222569 0.905517 0.423549 410 | 409 82.238 158.092 -0.474324 -0.0124721 0.0228732 0.905672 0.423178 411 | 410 81.6187 158.827 -0.49584 -0.0117377 0.0228573 0.905834 0.422854 412 | 411 81.0034 159.562 -0.518054 -0.010942 0.0227178 0.905929 0.422678 413 | 412 80.3845 160.292 -0.541088 -0.0106429 0.0218229 0.905993 0.422595 414 | 413 79.7644 161.016 -0.564147 -0.0109094 0.0205511 0.905943 0.42276 415 | 414 79.1488 161.736 -0.582374 -0.0111123 0.0197226 0.905714 0.423285 416 | 415 78.5444 162.45 -0.600675 -0.0114598 0.0191267 0.90555 0.423653 417 | 416 77.9342 163.168 -0.624063 -0.011927 0.0187725 0.905442 0.423887 418 | 417 77.3293 163.901 -0.639987 -0.0118941 0.0190506 0.905221 0.424347 419 | 418 76.7186 164.627 -0.661862 -0.0117085 0.0181873 0.905094 0.424662 420 | 419 76.1125 165.345 -0.679346 -0.0112194 0.0178642 0.904975 0.424942 421 | 420 75.525 166.047 -0.696646 -0.0108336 0.0183671 0.904901 0.425087 422 | 421 74.9328 166.77 -0.721669 -0.0108515 0.0198648 0.904646 0.425561 423 | 422 74.345 167.486 -0.736065 -0.0107906 0.0203481 0.904477 0.425901 424 | 423 73.7599 168.188 -0.752742 -0.0100642 0.0195761 0.904492 0.425923 425 | 424 73.1641 168.893 -0.76627 -0.00797427 0.0196294 0.904427 0.426101 426 | 425 72.5839 169.599 -0.774807 -0.0071751 0.0193656 0.904092 0.426838 427 | 426 72.0116 170.286 -0.797669 -0.00783457 0.0185323 0.903928 0.427211 428 | 427 71.4416 170.976 -0.808817 -0.00851891 0.018309 0.903801 0.427476 429 | 428 70.8811 171.651 -0.816233 -0.00858703 0.018184 0.903834 0.42741 430 | 429 70.3262 172.315 -0.828708 -0.00827093 0.0182533 0.903949 0.42717 431 | 430 69.7693 172.979 -0.833339 -0.00820361 0.018434 0.903981 0.427097 432 | 431 69.2378 173.624 -0.847069 -0.00830718 0.0180246 0.904008 0.427054 433 | 432 68.7099 174.254 -0.859493 -0.00854682 0.0177432 0.903996 0.427087 434 | 433 68.1829 174.881 -0.861043 -0.00848121 0.0177693 0.903946 0.427193 435 | 434 67.6761 175.493 -0.870686 -0.00876291 0.0183367 0.904039 0.426967 436 | 435 67.1748 176.097 -0.882497 -0.00961848 0.0186371 0.904077 0.426854 437 | 436 66.6773 176.71 -0.899162 -0.0104994 0.0192765 0.904056 0.42685 438 | 437 66.1685 177.325 -0.908813 -0.0111922 0.0200073 0.904059 0.426792 439 | 438 65.6902 177.908 -0.923372 -0.0113418 0.0210951 0.904117 0.426613 440 | 439 65.2137 178.486 -0.938348 -0.0113751 0.0221798 0.90419 0.426402 441 | 440 64.7507 179.048 -0.947789 -0.0112627 0.0226396 0.904281 0.426188 442 | 441 64.2864 179.598 -0.967244 -0.0112707 0.0228397 0.90454 0.425627 443 | 442 63.8523 180.134 -0.979229 -0.0108877 0.0234072 0.90484 0.424968 444 | 443 63.4053 180.661 -0.990982 -0.00996844 0.0241285 0.905405 0.423746 445 | 444 62.9568 181.183 -1.00323 -0.00886264 0.0250629 0.906266 0.42187 446 | 445 62.538 181.676 -1.01568 -0.00784814 0.0263413 0.907679 0.418763 447 | 446 62.1158 182.163 -1.02272 -0.00727053 0.0274064 0.909678 0.414344 448 | 447 61.6874 182.645 -1.03405 -0.00680434 0.0287267 0.912085 0.408936 449 | 448 61.2614 183.107 -1.04603 -0.00652419 0.029685 0.914929 0.40247 450 | 449 60.8266 183.563 -1.0579 -0.00608682 0.0309072 0.91814 0.395001 451 | 450 60.4071 183.991 -1.06535 -0.00520869 0.0326916 0.921892 0.386029 452 | 451 59.9755 184.408 -1.07163 -0.00453538 0.0342588 0.926121 0.375641 453 | 452 59.539 184.808 -1.08181 -0.00456611 0.0346831 0.930912 0.363564 454 | 453 59.0954 185.179 -1.0856 -0.00523259 0.033993 0.936154 0.349904 455 | 454 58.6253 185.53 -1.096 -0.00631891 0.0327479 0.941575 0.335147 456 | 455 58.173 185.853 -1.10119 -0.00697952 0.0314909 0.947126 0.319237 457 | 456 57.7244 186.141 -1.10491 -0.00762213 0.0304636 0.952961 0.301462 458 | 457 57.2608 186.42 -1.10568 -0.00845254 0.0306484 0.958894 0.281979 459 | 458 56.8018 186.655 -1.10682 -0.00904986 0.0285713 0.965039 0.260386 460 | 459 56.3503 186.865 -1.11389 -0.00915162 0.0247425 0.971069 0.237339 461 | 460 55.8632 187.048 -1.12116 -0.00897215 0.0192232 0.976584 0.214086 462 | 461 55.3852 187.198 -1.12305 -0.00844909 0.0147605 0.9814 0.191218 463 | 462 54.9378 187.316 -1.12203 -0.0070167 0.0115504 0.98571 0.16791 464 | 463 54.4405 187.436 -1.12265 -0.00602789 0.0101276 0.989564 0.143612 465 | 464 53.9855 187.525 -1.11853 -0.0059852 0.00965797 0.992868 0.118674 466 | 465 53.499 187.599 -1.11726 -0.00679989 0.0092859 0.995532 0.0937166 467 | 466 53.0035 187.642 -1.11797 -0.00870954 0.00582346 0.997598 0.0684765 468 | 467 52.5505 187.642 -1.1287 -0.0111057 0.00167737 0.998997 0.0433428 469 | 468 52.0621 187.619 -1.14126 -0.0123886 0.000417618 0.999764 0.0178497 470 | 469 51.5863 187.587 -1.13958 -0.0122159 0.00217291 0.999891 -0.00796462 471 | 470 51.1488 187.542 -1.1142 -0.01163 0.00529149 0.999348 -0.0337601 472 | 471 50.6889 187.481 -1.1256 -0.0101724 0.00741425 0.998155 -0.0593988 473 | 472 50.2653 187.397 -1.12323 -0.00938998 0.00820049 0.996336 -0.0846149 474 | 473 49.8261 187.281 -1.13036 -0.00800888 0.00807061 0.993911 -0.109597 475 | 474 49.3887 187.133 -1.13689 -0.00702604 0.00850425 0.990842 -0.134573 476 | 475 49.0047 186.971 -1.14729 -0.00693756 0.0112303 0.987089 -0.159629 477 | 476 48.5783 186.812 -1.12321 -0.00692475 0.0121648 0.982908 -0.183564 478 | 477 48.1763 186.631 -1.13579 -0.00713979 0.0103129 0.978535 -0.2057 479 | 478 47.754 186.418 -1.14202 -0.00896323 0.00916342 0.973942 -0.226436 480 | 479 47.3372 186.183 -1.13678 -0.0111272 0.0101614 0.969354 -0.245205 481 | 480 46.9403 185.943 -1.13055 -0.012944 0.011704 0.965007 -0.261643 482 | 481 46.5424 185.681 -1.12447 -0.0134821 0.0116334 0.96094 -0.276182 483 | 482 46.1608 185.405 -1.13395 -0.0135764 0.0111936 0.957284 -0.288613 484 | 483 45.7631 185.121 -1.13321 -0.0132235 0.0103202 0.954096 -0.299031 485 | 484 45.3675 184.829 -1.13694 -0.0127975 0.0100303 0.951442 -0.307397 486 | 485 44.9733 184.52 -1.13558 -0.012485 0.00977164 0.949315 -0.313927 487 | 486 44.5611 184.196 -1.14497 -0.0115541 0.00869863 0.947657 -0.318963 488 | 487 44.1535 183.857 -1.14277 -0.0102511 0.00819245 0.946321 -0.322961 489 | 488 43.7385 183.511 -1.1464 -0.00939584 0.00797176 0.94524 -0.326144 490 | 489 43.305 183.17 -1.15003 -0.00946161 0.00928693 0.944353 -0.328667 491 | 490 42.8804 182.823 -1.14323 -0.00988676 0.0106966 0.943597 -0.330776 492 | 491 42.4524 182.467 -1.1445 -0.00898247 0.0105075 0.943024 -0.332438 493 | 492 42.0242 182.102 -1.1433 -0.00747563 0.00794253 0.942678 -0.333526 494 | 493 41.5798 181.725 -1.15002 -0.00693438 0.00660859 0.94241 -0.334324 495 | 494 41.1083 181.345 -1.1531 -0.00788756 0.00808219 0.942254 -0.334709 496 | 495 40.6278 180.963 -1.15125 -0.00888659 0.0103454 0.942243 -0.334651 497 | 496 40.1461 180.568 -1.14929 -0.00874335 0.0113673 0.94238 -0.334236 498 | 497 39.6556 180.152 -1.15316 -0.00623339 0.0104696 0.942528 -0.333904 499 | 498 39.1466 179.736 -1.14567 -0.00249362 0.00917411 0.94266 -0.333619 500 | 499 38.6242 179.309 -1.1468 9.73192e-05 0.00872434 0.94281 -0.333216 501 | 500 38.0793 178.872 -1.13629 -0.000326679 0.00993069 0.942875 -0.332997 502 | 501 37.5272 178.426 -1.13203 -0.0015138 0.0102595 0.942956 -0.332754 503 | 502 36.966 177.961 -1.12778 -0.00183025 0.00744052 0.943034 -0.332607 504 | 503 36.3928 177.485 -1.12281 -0.00181249 0.00538115 0.942989 -0.332774 505 | 504 35.8009 176.999 -1.1145 -0.00226337 0.00412358 0.942937 -0.332937 506 | 505 35.189 176.506 -1.11685 -0.00361568 0.00361776 0.942873 -0.333114 507 | 506 34.5677 176.004 -1.11822 -0.00562074 0.00369522 0.942941 -0.332892 508 | 507 33.9396 175.48 -1.12713 -0.00611615 0.00226296 0.942962 -0.332837 509 | 508 33.303 174.958 -1.11984 -0.00473574 0.001295 0.94291 -0.333013 510 | 509 32.6657 174.435 -1.11288 -0.00329191 0.000912681 0.942861 -0.333169 511 | 510 31.999 173.902 -1.1132 -0.00366307 0.000800508 0.942754 -0.333469 512 | 511 31.3244 173.357 -1.13451 -0.00691014 0.00359733 0.942758 -0.333387 513 | 512 30.6409 172.799 -1.13376 -0.00828417 0.00370427 0.942789 -0.333267 514 | 513 29.9477 172.242 -1.12992 -0.00858001 0.00535699 0.942709 -0.333464 515 | 514 29.2479 171.684 -1.12246 -0.00756999 0.00710071 0.942719 -0.333426 516 | 515 28.5424 171.118 -1.12385 -0.00627826 0.00915751 0.942654 -0.333588 517 | 516 27.8326 170.537 -1.12208 -0.00535368 0.0105702 0.942655 -0.333559 518 | 517 27.1022 169.946 -1.1151 -0.00479528 0.00962125 0.942793 -0.333206 519 | 518 26.3807 169.354 -1.11283 -0.00554449 0.00896779 0.942976 -0.332695 520 | 519 25.651 168.76 -1.11068 -0.00704844 0.00814448 0.943103 -0.332326 521 | 520 24.9143 168.167 -1.11061 -0.00828588 0.00822409 0.943145 -0.332177 522 | 521 24.183 167.589 -1.10541 -0.00977597 0.0102313 0.943172 -0.332002 523 | 522 23.445 167.004 -1.09417 -0.0115362 0.0128053 0.94319 -0.331808 524 | 523 22.7198 166.421 -1.09834 -0.0135205 0.0138364 0.943236 -0.331558 525 | 524 21.9859 165.836 -1.10452 -0.0166793 0.0149997 0.943243 -0.331345 526 | 525 21.2465 165.246 -1.11926 -0.0194163 0.015691 0.94308 -0.331629 527 | 526 20.5203 164.663 -1.11579 -0.0196408 0.0164297 0.943104 -0.331511 528 | 527 19.8064 164.084 -1.11713 -0.0160829 0.0169711 0.943261 -0.331228 529 | 528 19.0886 163.506 -1.11748 -0.0117592 0.0171419 0.943516 -0.330675 530 | 529 18.3582 162.925 -1.11539 -0.0103736 0.0180821 0.943665 -0.330245 531 | 530 17.6341 162.342 -1.11672 -0.0113822 0.0178649 0.943725 -0.330052 532 | 531 16.925 161.766 -1.10841 -0.0127322 0.0176019 0.94395 -0.329374 533 | 532 16.212 161.195 -1.10282 -0.0135395 0.0177171 0.94406 -0.329019 534 | 533 15.5103 160.636 -1.10214 -0.0132153 0.0165065 0.944567 -0.327636 535 | 534 14.7951 160.074 -1.10109 -0.0129381 0.0151364 0.94558 -0.32478 536 | 535 14.0756 159.516 -1.10146 -0.0126222 0.0139645 0.947011 -0.32065 537 | 536 13.3649 158.974 -1.09453 -0.0127254 0.0144186 0.948895 -0.315007 538 | 537 12.6395 158.447 -1.09728 -0.0132621 0.0150154 0.951112 -0.308196 539 | 538 11.9067 157.936 -1.10229 -0.0150002 0.0162255 0.953719 -0.299887 540 | 539 11.164 157.439 -1.1044 -0.0166915 0.0168304 0.956725 -0.290028 541 | 540 10.4191 156.968 -1.10832 -0.017834 0.0176408 0.960145 -0.278374 542 | 541 9.65964 156.519 -1.11037 -0.0183675 0.0189001 0.963906 -0.264934 543 | 542 8.8814 156.089 -1.13076 -0.0188874 0.0201135 0.967879 -0.249899 544 | 543 8.10529 155.691 -1.12874 -0.0197645 0.0211442 0.971887 -0.233661 545 | 544 7.31807 155.316 -1.15635 -0.019206 0.0234176 0.975583 -0.217534 546 | 545 6.53583 154.973 -1.1522 -0.01549 0.0243726 0.979116 -0.201242 547 | 546 5.74529 154.667 -1.14565 -0.0115598 0.0255302 0.982404 -0.184656 548 | 547 4.9363 154.368 -1.14586 -0.00812286 0.0245257 0.985365 -0.168489 549 | 548 4.11446 154.094 -1.15692 -0.00712478 0.0224726 0.987998 -0.152659 550 | 549 3.28239 153.841 -1.15534 -0.00659894 0.0215613 0.990175 -0.138001 551 | 550 2.44704 153.618 -1.14789 -0.00617011 0.0226909 0.991884 -0.124952 552 | 551 1.59594 153.423 -1.13301 -0.00571433 0.0240487 0.993209 -0.113688 553 | 552 0.752426 153.237 -1.12555 -0.00643166 0.0234789 0.994295 -0.103855 554 | 553 -0.1142 153.066 -1.15084 -0.00832266 0.0224617 0.995234 -0.0945273 555 | 554 -1.01293 152.907 -1.15115 -0.00952422 0.0223855 0.996068 -0.0851853 556 | 555 -1.88349 152.76 -1.15696 -0.00946232 0.0223577 0.996795 -0.0762216 557 | 556 -2.78348 152.63 -1.15069 -0.0076947 0.0213963 0.997427 -0.0679936 558 | 557 -3.683 152.514 -1.14964 -0.00638915 0.0227873 0.997878 -0.0606515 559 | 558 -4.60074 152.412 -1.15657 -0.0079942 0.0254185 0.99812 -0.0551939 560 | 559 -5.54812 152.325 -1.17278 -0.012314 0.0293995 0.998155 -0.0516857 561 | 560 -6.48245 152.236 -1.19524 -0.0163717 0.0310396 0.998137 -0.0499068 562 | 561 -7.4445 152.142 -1.20182 -0.0172552 0.0303943 0.998177 -0.0491969 563 | 562 -8.38846 152.044 -1.2219 -0.0158896 0.0287028 0.998264 -0.048925 564 | 563 -9.34945 151.946 -1.23186 -0.0138178 0.0262143 0.998385 -0.048466 565 | 564 -10.3357 151.833 -1.25318 -0.0125443 0.0217578 0.998519 -0.0482635 566 | 565 -11.3126 151.721 -1.26598 -0.0122945 0.0191964 0.998577 -0.0482055 567 | 566 -12.3069 151.618 -1.27976 -0.013159 0.0180763 0.99858 -0.0483581 568 | 567 -13.3231 151.513 -1.29467 -0.0138567 0.0175088 0.998556 -0.0488583 569 | 568 -14.3337 151.41 -1.30722 -0.0142263 0.0173983 0.998526 -0.0494074 570 | 569 -15.3622 151.306 -1.32114 -0.0135573 0.0164043 0.99853 -0.0498495 571 | 570 -16.3946 151.186 -1.33919 -0.0127451 0.0158389 0.998513 -0.0505874 572 | 571 -17.4234 151.071 -1.34809 -0.0117366 0.0144288 0.998525 -0.0510174 573 | 572 -18.4657 150.955 -1.36157 -0.0110579 0.0131336 0.998555 -0.0509206 574 | 573 -19.5166 150.846 -1.36696 -0.0111158 0.0124782 0.998596 -0.0502748 575 | 574 -20.5656 150.736 -1.37895 -0.0114448 0.0113911 0.998647 -0.04944 576 | 575 -21.6354 150.618 -1.38543 -0.0116113 0.0113659 0.99869 -0.0485176 577 | 576 -22.6823 150.506 -1.39562 -0.0118428 0.0107313 0.99873 -0.0477758 578 | 577 -23.7474 150.406 -1.39974 -0.0124372 0.0108141 0.998754 -0.0471069 579 | 578 -24.7881 150.298 -1.40957 -0.0135133 0.0101195 0.998753 -0.0469806 580 | 579 -25.8392 150.2 -1.42627 -0.014518 0.00989907 0.998761 -0.0465532 581 | 580 -26.8875 150.1 -1.43194 -0.0140082 0.00948652 0.998803 -0.0458959 582 | 581 -27.9294 149.994 -1.4443 -0.0130048 0.00882338 0.998838 -0.0455682 583 | 582 -28.96 149.889 -1.45711 -0.0122187 0.00768961 0.998874 -0.0451819 584 | 583 -30.0079 149.792 -1.4706 -0.0123418 0.00765813 0.998901 -0.0445593 585 | 584 -31.0426 149.69 -1.47823 -0.012712 0.00648014 0.998934 -0.0438965 586 | 585 -32.0707 149.598 -1.49333 -0.0132298 0.00558778 0.998985 -0.042684 587 | 586 -33.0957 149.5 -1.50367 -0.0135038 0.0048316 0.999042 -0.0413385 588 | 587 -34.1198 149.41 -1.50991 -0.0130651 0.00493756 0.99911 -0.0398114 589 | 588 -35.1446 149.323 -1.51437 -0.012731 0.00457876 0.999181 -0.0381301 590 | 589 -36.1762 149.245 -1.53755 -0.0132473 0.00340854 0.999233 -0.0366975 591 | 590 -37.197 149.166 -1.54272 -0.0138004 0.00387929 0.999274 -0.0353021 592 | 591 -38.2295 149.084 -1.55122 -0.0143904 0.00470028 0.999305 -0.034053 593 | 592 -39.2464 149.018 -1.56411 -0.0147488 0.00483738 0.999342 -0.0327677 594 | 593 -40.2462 148.947 -1.57746 -0.0145235 0.00377355 0.999389 -0.0315792 595 | 594 -41.2687 148.876 -1.59009 -0.0141327 0.00340684 0.999423 -0.0306841 596 | 595 -42.2826 148.804 -1.60602 -0.01415 0.00308436 0.999448 -0.0299048 597 | 596 -43.2871 148.746 -1.62006 -0.0141797 0.00270888 0.999467 -0.0292872 598 | 597 -44.2915 148.683 -1.62792 -0.0136656 0.00272165 0.999487 -0.028835 599 | 598 -45.2915 148.618 -1.62484 -0.0119692 0.00199123 0.99952 -0.0284988 600 | 599 -46.2888 148.553 -1.63771 -0.0102279 0.000917314 0.999543 -0.0284215 601 | 600 -47.2801 148.49 -1.64802 -0.00977329 0.000591184 0.999542 -0.0286203 602 | 601 -48.256 148.435 -1.65385 -0.0102233 0.00127859 0.99953 -0.0288699 603 | 602 -49.2411 148.371 -1.65837 -0.0105537 0.0014368 0.999514 -0.0292815 604 | 603 -50.2214 148.319 -1.66331 -0.0111765 0.00186358 0.999497 -0.0296179 605 | 604 -51.2114 148.254 -1.67089 -0.0115984 0.00170614 0.999478 -0.0301122 606 | 605 -52.187 148.186 -1.6728 -0.0120174 0.00104542 0.99946 -0.0305645 607 | 606 -53.1427 148.121 -1.68294 -0.0120261 0.00105666 0.999448 -0.0309672 608 | 607 -54.1221 148.047 -1.68753 -0.0116703 0.00112778 0.999435 -0.0315129 609 | 608 -55.0878 147.986 -1.68874 -0.0112128 0.00255325 0.999413 -0.0322755 610 | 609 -56.031 147.923 -1.69194 -0.010632 0.00232959 0.999376 -0.0336121 611 | 610 -56.9964 147.85 -1.69854 -0.010363 0.00243536 0.999328 -0.0350674 612 | 611 -57.9285 147.777 -1.70407 -0.00976772 0.00235016 0.999288 -0.0363693 613 | 612 -58.8693 147.699 -1.70299 -0.00934881 0.00255186 0.999254 -0.0373867 614 | 613 -59.807 147.628 -1.70592 -0.00958951 0.00307054 0.99923 -0.0379257 615 | 614 -60.7387 147.552 -1.71224 -0.0104751 0.0020952 0.99922 -0.0380079 616 | 615 -61.6696 147.473 -1.72205 -0.0114051 0.00175217 0.99922 -0.0377574 617 | 616 -62.5756 147.403 -1.72597 -0.0118769 0.00160351 0.999235 -0.037217 618 | 617 -63.4767 147.33 -1.73095 -0.0120741 0.00132481 0.999257 -0.0365844 619 | 618 -64.3582 147.263 -1.72879 -0.0121228 0.00151542 0.999295 -0.0354904 620 | 619 -65.2192 147.201 -1.73812 -0.0122052 0.000411643 0.999363 -0.0335467 621 | 620 -66.0716 147.14 -1.74063 -0.0122837 0.000573799 0.999447 -0.030884 622 | 621 -66.9003 147.09 -1.74634 -0.0124594 0.00144589 0.999548 -0.0273302 623 | 622 -67.7105 147.049 -1.74983 -0.0126847 0.002183 0.999642 -0.0234419 624 | 623 -68.507 147.018 -1.7602 -0.0132841 0.00292663 0.999721 -0.019307 625 | 624 -69.2745 147.001 -1.75504 -0.0137108 0.00488127 0.999779 -0.0151846 626 | 625 -70.0128 146.986 -1.7572 -0.0141099 0.0065331 0.999814 -0.0114031 627 | 626 -70.7299 146.973 -1.76188 -0.0144747 0.00726331 0.999839 -0.00773971 628 | 627 -71.4147 146.96 -1.77013 -0.0143394 0.00736631 0.99986 -0.0045879 629 | 628 -72.0764 146.961 -1.77528 -0.0140817 0.00822411 0.999866 -0.00119241 630 | 629 -72.7086 146.966 -1.77348 -0.0139829 0.0086261 0.999863 0.00185619 631 | 630 -73.3335 146.972 -1.78133 -0.0136601 0.00925118 0.999854 0.00451326 632 | 631 -73.9114 146.987 -1.78039 -0.0135555 0.0102854 0.999831 0.00701059 633 | 632 -74.4754 146.998 -1.78594 -0.0140703 0.0112417 0.999795 0.00925628 634 | 633 -75.0067 147.012 -1.79324 -0.0149282 0.0113469 0.99976 0.0113276 635 | 634 -75.5022 147.034 -1.79306 -0.0153992 0.0117483 0.999723 0.0133578 636 | 635 -75.9673 147.045 -1.79495 -0.0158787 0.0122336 0.999689 0.0148348 637 | 636 -76.4075 147.066 -1.8001 -0.0162687 0.0128692 0.999651 0.016359 638 | 637 -76.8268 147.083 -1.80282 -0.0164391 0.014126 0.999612 0.0174811 639 | 638 -77.1901 147.105 -1.80691 -0.016891 0.0144585 0.99959 0.0180164 640 | 639 -77.528 147.114 -1.8134 -0.0173366 0.014498 0.999577 0.018276 641 | 640 -77.8424 147.108 -1.81935 -0.0177476 0.0142925 0.999578 0.017992 642 | 641 -78.1079 147.113 -1.81461 -0.0174594 0.0130212 0.99961 0.0174632 643 | 642 -78.358 147.114 -1.81874 -0.0171933 0.0122798 0.999638 0.0166278 644 | 643 -78.586 147.117 -1.82053 -0.0169563 0.0112689 0.999674 0.0154393 645 | 644 -78.7915 147.116 -1.8252 -0.0163201 0.0109713 0.999707 0.0141355 646 | 645 -78.9883 147.114 -1.82208 -0.0151331 0.0106659 0.999747 0.0128063 647 | 646 -79.1797 147.12 -1.82112 -0.0141058 0.0106609 0.999777 0.0115539 648 | 647 -79.3633 147.127 -1.82703 -0.0139767 0.0111933 0.999785 0.0104541 649 | 648 -79.5457 147.121 -1.83081 -0.014432 0.0106549 0.999797 0.00918369 650 | 649 -79.7147 147.12 -1.83527 -0.0145951 0.0101043 0.999811 0.00790382 651 | 650 -79.8723 147.119 -1.8386 -0.0142755 0.00909064 0.999836 0.00638066 652 | 651 -80.0146 147.117 -1.83714 -0.0140133 0.00940516 0.999847 0.00455609 653 | 652 -80.1428 147.115 -1.83712 -0.01366 0.00995467 0.999854 0.00233897 654 | 653 -80.2812 147.121 -1.83754 -0.0135104 0.0101871 0.999857 -0.000330169 655 | 654 -80.4128 147.118 -1.84099 -0.0133825 0.00966178 0.999857 -0.0036557 656 | 655 -80.5322 147.098 -1.84102 -0.0132745 0.00882994 0.999844 -0.00756754 657 | 656 -80.6361 147.084 -1.84071 -0.0134275 0.00769104 0.999814 -0.0114982 658 | 657 -80.7328 147.072 -1.8435 -0.0138854 0.00696057 0.999766 -0.0150418 659 | 658 -80.8162 147.058 -1.84322 -0.0140591 0.00619143 0.999717 -0.0181776 660 | 659 -80.8689 147.051 -1.84549 -0.0142088 0.00588376 0.999668 -0.0206554 661 | 660 -80.9215 147.041 -1.84364 -0.0138646 0.00606865 0.999628 -0.0227029 662 | 661 -80.9541 147.041 -1.8463 -0.0137471 0.00597145 0.999592 -0.0243149 663 | 662 -80.9853 147.038 -1.84493 -0.0136329 0.00603965 0.999565 -0.025437 664 | 663 -80.9996 147.038 -1.84399 -0.0134702 0.00584878 0.999546 -0.0262998 665 | 664 -81.0042 147.034 -1.84606 -0.0135395 0.0057334 0.999534 -0.0267592 666 | 665 -81.0101 147.035 -1.84572 -0.0135489 0.00576472 0.999534 -0.0267213 667 | 666 -81.0059 147.037 -1.84437 -0.0132466 0.00614736 0.999536 -0.0267296 668 | 667 -81.0008 147.04 -1.84109 -0.0126875 0.00621628 0.999541 -0.0268097 669 | 668 -81.0058 147.04 -1.83968 -0.0122946 0.00606331 0.99955 -0.0266802 670 | 669 -81.003 147.035 -1.84339 -0.0125684 0.00599543 0.999545 -0.0267531 671 | 670 -80.9991 147.034 -1.84158 -0.0124514 0.00606354 0.999544 -0.0268186 672 | 671 -81.0044 147.033 -1.84216 -0.0124182 0.00611296 0.999546 -0.0267428 673 | 672 -81.0023 147.039 -1.84541 -0.012541 0.00610766 0.999544 -0.0267938 674 | 673 -81.0006 147.035 -1.84451 -0.0123993 0.00621674 0.999545 -0.0267894 675 | 674 -81.0008 147.033 -1.84558 -0.0124839 0.00620514 0.999542 -0.0268681 676 | 675 -81.0032 147.034 -1.84565 -0.0125475 0.0062201 0.999539 -0.0269469 677 | 676 -81.0053 147.041 -1.84447 -0.0124907 0.00620666 0.999539 -0.0269528 678 | 677 -81.0057 147.039 -1.84498 -0.0125271 0.00615539 0.999537 -0.0270458 679 | 678 -81.0071 147.034 -1.84561 -0.012496 0.00622049 0.999535 -0.0271184 680 | 679 -81.004 147.034 -1.84456 -0.0124758 0.00626436 0.999533 -0.0271822 681 | 680 -81.0061 147.032 -1.84382 -0.0125314 0.00627034 0.99953 -0.0272513 682 | 681 -81.0079 147.034 -1.84399 -0.0124588 0.00626466 0.99953 -0.0272831 683 | 682 -81.0077 147.035 -1.84318 -0.0124659 0.00632206 0.999527 -0.027389 684 | 683 -81.0047 147.035 -1.84447 -0.0125024 0.00635049 0.999525 -0.0274353 685 | 684 -81.0049 147.034 -1.84338 -0.0124581 0.00656704 0.99952 -0.0275814 686 | 685 -81.0028 147.036 -1.84074 -0.0125179 0.00663241 0.999514 -0.0277556 687 | 686 -81.0068 147.035 -1.8431 -0.012458 0.00671551 0.999507 -0.0280355 688 | 687 -81.0069 147.037 -1.84259 -0.0124234 0.00675474 0.999501 -0.028253 689 | 688 -81.0079 147.039 -1.84319 -0.0124563 0.00673719 0.999495 -0.02846 690 | 689 -81.0065 147.039 -1.84146 -0.0125203 0.00686335 0.999493 -0.0284739 691 | 690 -81.0078 147.038 -1.84279 -0.0123926 0.00688502 0.999495 -0.0284494 692 | 691 -81.0102 147.037 -1.84153 -0.0125203 0.00678383 0.99949 -0.0285954 693 | 692 -81.0077 147.037 -1.8428 -0.0124469 0.00708166 0.999487 -0.0286545 694 | 693 -81.0077 147.04 -1.8414 -0.0125474 0.00697793 0.999484 -0.0287471 695 | 694 -81.0077 147.04 -1.84053 -0.0125448 0.00701798 0.99948 -0.0288573 696 | 695 -81.0098 147.041 -1.8412 -0.0125889 0.0071079 0.999478 -0.0288879 697 | 696 -81.0081 147.04 -1.84146 -0.0126037 0.0071827 0.999475 -0.0289639 698 | 697 -81.0064 147.039 -1.84267 -0.0125707 0.00706413 0.999474 -0.0290417 699 | 698 -81.0079 147.039 -1.84184 -0.0126217 0.00713473 0.999473 -0.0290547 700 | 699 -81.0105 147.039 -1.84235 -0.0125044 0.00724269 0.999471 -0.0291515 701 | 700 -81.0084 147.04 -1.84124 -0.0126303 0.0072675 0.999466 -0.0292376 702 | 701 -81.0105 147.039 -1.84144 -0.01269 0.00731939 0.999462 -0.0293515 703 | 702 -81.0128 147.039 -1.84235 -0.0126208 0.00733902 0.999461 -0.0293922 704 | 703 -81.0121 147.036 -1.84287 -0.0126433 0.0074539 0.99946 -0.0293835 705 | 704 -81.0092 147.036 -1.84299 -0.0126441 0.00751265 0.999457 -0.0294823 706 | 705 -81.0124 147.038 -1.84305 -0.0126746 0.00733611 0.999457 -0.0295011 707 | 706 -81.0098 147.037 -1.84341 -0.0126183 0.0073709 0.999459 -0.0294783 708 | 707 -81.0106 147.035 -1.84148 -0.0126619 0.00742812 0.999456 -0.0295269 709 | 708 -81.009 147.038 -1.84165 -0.0127018 0.00744574 0.999457 -0.0294751 710 | 709 -81.0076 147.037 -1.8425 -0.0126618 0.0073895 0.999457 -0.0295175 711 | 710 -81.0096 147.039 -1.84132 -0.0127008 0.00731444 0.999457 -0.0295233 712 | 711 -81.0119 147.038 -1.84216 -0.0126559 0.0073375 0.999457 -0.0295082 713 | 712 -81.0085 147.04 -1.84042 -0.0127413 0.0073484 0.999456 -0.0295087 714 | 713 -81.0122 147.038 -1.83936 -0.0127453 0.00737023 0.999456 -0.0295096 715 | 714 -81.0122 147.039 -1.84032 -0.0127571 0.00739444 0.999455 -0.0295409 716 | 715 -81.0141 147.039 -1.83994 -0.012735 0.00734025 0.999455 -0.0295704 717 | 716 -81.0114 147.038 -1.84133 -0.0126454 0.00718363 0.999458 -0.029523 718 | 717 -81.0165 147.037 -1.84052 -0.0126545 0.00730373 0.999446 -0.0298895 719 | 718 -81.0172 147.034 -1.83996 -0.0124711 0.0070871 0.999415 -0.0310538 720 | 719 -81.0216 147.033 -1.84188 -0.0122399 0.00684027 0.999387 -0.0320888 721 | 720 -81.0427 147.028 -1.84261 -0.0121766 0.00664861 0.99934 -0.0335769 722 | 721 -81.0575 147.026 -1.84118 -0.012184 0.0067066 0.999255 -0.0359912 723 | 722 -81.0777 147.019 -1.83989 -0.0121232 0.00675052 0.999149 -0.0388485 724 | 723 -81.1046 147.008 -1.84 -0.0121695 0.00640764 0.999023 -0.0419948 725 | 724 -81.1346 146.998 -1.84092 -0.0122021 0.00634619 0.998854 -0.0458524 726 | 725 -81.1639 146.987 -1.83867 -0.0121822 0.00627006 0.998638 -0.0503401 727 | 726 -81.2018 146.975 -1.84009 -0.0121911 0.00619133 0.998384 -0.055164 728 | 727 -81.2478 146.963 -1.84178 -0.0122152 0.00594688 0.998077 -0.060481 729 | 728 -81.2929 146.946 -1.84205 -0.0122829 0.00599003 0.997697 -0.0664357 730 | 729 -81.3384 146.931 -1.84222 -0.0120658 0.00593981 0.997241 -0.0729983 731 | 730 -81.3957 146.911 -1.8429 -0.0116441 0.00587786 0.996695 -0.0801851 732 | 731 -81.4567 146.892 -1.84359 -0.010695 0.00556872 0.996032 -0.0881802 733 | 732 -81.5392 146.863 -1.84438 -0.0096877 0.0049692 0.995234 -0.0969013 734 | 733 -81.6517 146.817 -1.84725 -0.00907396 0.00421707 0.994331 -0.105861 735 | 734 -81.7192 146.793 -1.85226 -0.00931182 0.00406629 0.993305 -0.115077 736 | 735 -81.8766 146.739 -1.852 -0.0100268 0.00446523 0.992127 -0.124753 737 | 736 -82.0104 146.695 -1.84613 -0.010977 0.00505438 0.990736 -0.13526 738 | 737 -82.1709 146.625 -1.85035 -0.0116055 0.0047101 0.989094 -0.146755 739 | 738 -82.3321 146.552 -1.85326 -0.0127635 0.00404781 0.987219 -0.158809 740 | 739 -82.4909 146.481 -1.85818 -0.0139113 0.00393722 0.98511 -0.171315 741 | 740 -82.6841 146.394 -1.85627 -0.0144137 0.00465496 0.982763 -0.184249 742 | 741 -82.8716 146.3 -1.86098 -0.0157011 0.00518342 0.980037 -0.198127 743 | 742 -83.049 146.197 -1.86097 -0.0174025 0.0055655 0.976812 -0.213317 744 | 743 -83.2602 146.066 -1.86261 -0.0182794 0.00603068 0.973046 -0.229806 745 | 744 -83.4605 145.923 -1.86488 -0.0179312 0.00629227 0.968568 -0.248023 746 | 745 -83.6434 145.779 -1.8674 -0.0167973 0.00564085 0.96325 -0.268023 747 | 746 -83.8863 145.583 -1.87635 -0.0154479 0.00484271 0.957059 -0.289439 748 | 747 -84.0972 145.391 -1.88366 -0.0145396 0.00473222 0.949774 -0.312563 749 | 748 -84.3612 145.146 -1.8862 -0.0138292 0.00657847 0.941322 -0.337163 750 | 749 -84.6109 144.884 -1.8878 -0.012797 0.00844479 0.932004 -0.362124 751 | 750 -84.845 144.613 -1.89737 -0.0112185 0.00955312 0.922131 -0.386597 752 | 751 -85.1428 144.257 -1.91348 -0.0108302 0.00958756 0.911611 -0.410799 753 | 752 -85.4109 143.888 -1.91657 -0.0111703 0.0103178 0.900436 -0.434722 754 | 753 -85.6487 143.505 -1.91321 -0.0123284 0.0106646 0.88847 -0.458646 755 | 754 -85.928 143.042 -1.92739 -0.0135048 0.0100426 0.87578 -0.482418 756 | 755 -86.1446 142.588 -1.93348 0.0158691 -0.010004 -0.862488 0.50573 757 | 756 -86.4089 142.058 -1.94141 0.0187426 -0.0105305 -0.848089 0.529417 758 | 757 -86.6168 141.523 -1.94196 0.0213128 -0.0109806 -0.833085 0.552624 759 | 758 -86.7757 140.986 -1.95459 0.0232039 -0.0107365 -0.817835 0.574884 760 | 759 -86.9721 140.366 -1.96964 0.0247546 -0.0106449 -0.802246 0.596385 761 | 760 -87.0946 139.766 -1.98296 0.0259187 -0.0110038 -0.786936 0.616391 762 | 761 -87.233 139.093 -1.98869 0.0262293 -0.012304 -0.772245 0.634664 763 | 762 -87.3295 138.408 -1.99684 0.0255794 -0.012817 -0.759087 0.65036 764 | 763 -87.3998 137.706 -2.01715 0.0243811 -0.0130599 -0.747867 0.663272 765 | 764 -87.4642 136.957 -2.0268 0.0227805 -0.0134006 -0.738463 0.673776 766 | 765 -87.5149 136.184 -2.033 0.0216964 -0.0141511 -0.73111 0.681767 767 | 766 -87.557 135.391 -2.04244 0.0214279 -0.014947 -0.72517 0.688074 768 | 767 -87.5832 134.573 -2.04493 0.0215214 -0.0159403 -0.719968 0.69349 769 | 768 -87.6011 133.73 -2.04872 0.0212883 -0.0175326 -0.715091 0.698487 770 | 769 -87.6067 132.87 -2.04495 0.0206684 -0.0194493 -0.710059 0.70357 771 | 770 -87.5915 131.996 -2.03933 0.019257 -0.0205055 -0.70518 0.70847 772 | 771 -87.564 131.088 -2.04148 0.0178645 -0.0198629 -0.7007 0.712956 773 | 772 -87.5412 130.157 -2.0342 0.0164003 -0.0185103 -0.697389 0.716266 774 | 773 -87.4985 129.21 -2.02567 0.0145023 -0.0170708 -0.695345 0.718327 775 | 774 -87.4569 128.238 -2.01314 0.0134944 -0.0161771 -0.694535 0.719151 776 | 775 -87.4151 127.241 -2.00847 0.0134888 -0.0156395 -0.694306 0.719384 777 | 776 -87.3704 126.223 -1.99853 0.0142018 -0.0155611 -0.693771 0.719887 778 | 777 -87.3286 125.18 -1.99571 0.0147707 -0.0158099 -0.692817 0.720789 779 | 778 -87.2747 124.132 -1.98939 0.0147958 -0.0158673 -0.691298 0.722244 780 | 779 -87.2266 123.052 -1.97955 0.0146851 -0.0160568 -0.689551 0.72391 781 | 780 -87.1627 121.967 -1.97062 0.0142356 -0.0159284 -0.687931 0.725462 782 | 781 -87.0899 120.863 -1.96158 0.0138594 -0.0152974 -0.686121 0.727195 783 | 782 -87.0217 119.74 -1.95143 0.014968 -0.0149932 -0.684269 0.728922 784 | 783 -86.9444 118.607 -1.94817 0.0166708 -0.014186 -0.682414 0.730638 785 | 784 -86.8556 117.453 -1.93911 0.0179122 -0.0138307 -0.680901 0.732026 786 | 785 -86.7635 116.291 -1.93194 0.0176399 -0.0138296 -0.680132 0.732747 787 | 786 -86.6713 115.113 -1.92293 0.0162393 -0.0135117 -0.680165 0.732754 788 | 787 -86.5789 113.911 -1.92085 0.0160856 -0.013454 -0.680709 0.732254 789 | 788 -86.4842 112.716 -1.91299 0.0170317 -0.0131559 -0.680983 0.731982 790 | 789 -86.3985 111.51 -1.90544 0.0185208 -0.0131899 -0.68128 0.731669 791 | 790 -86.3098 110.309 -1.8975 0.0194033 -0.0128858 -0.681476 0.73147 792 | 791 -86.2206 109.114 -1.88873 0.0196879 -0.0126062 -0.681655 0.7313 793 | 792 -86.1398 107.92 -1.88329 0.0200631 -0.0130094 -0.681999 0.730962 794 | 793 -86.0517 106.733 -1.87161 0.0196175 -0.0135249 -0.682191 0.730785 795 | 794 -85.9676 105.546 -1.85981 0.0188473 -0.0140104 -0.682328 0.730669 796 | 795 -85.8811 104.356 -1.84917 0.0181727 -0.0138111 -0.682558 0.730475 797 | 796 -85.8006 103.169 -1.84017 0.0189507 -0.0130222 -0.682828 0.730217 798 | 797 -85.7146 101.978 -1.83304 0.0199636 -0.0126631 -0.683115 0.729928 799 | 798 -85.6263 100.784 -1.8218 0.0189501 -0.0124258 -0.683263 0.72982 800 | 799 -85.5538 99.6066 -1.81123 0.0182228 -0.0131741 -0.683515 0.72959 801 | 800 -85.4721 98.4237 -1.7911 0.0177627 -0.013558 -0.683571 0.729542 802 | 801 -85.3861 97.2472 -1.79099 0.0182805 -0.0128806 -0.683699 0.729421 803 | 802 -85.3058 96.0797 -1.78282 0.0189986 -0.0113424 -0.683927 0.729215 804 | 803 -85.2259 94.9073 -1.77596 0.0196539 -0.0103543 -0.684026 0.729119 805 | 804 -85.144 93.7475 -1.76699 0.0179612 -0.00929449 -0.684321 0.728901 806 | 805 -85.0658 92.5853 -1.75976 0.0171676 -0.00950352 -0.684382 0.728859 807 | 806 -84.9842 91.4225 -1.75373 0.0167534 -0.00943667 -0.684545 0.728717 808 | 807 -84.9054 90.2762 -1.74575 0.0165166 -0.00877055 -0.684599 0.72868 809 | 808 -84.8325 89.1212 -1.74091 0.017419 -0.00882408 -0.684552 0.728702 810 | 809 -84.7535 87.9667 -1.73155 0.0178978 -0.00931796 -0.684521 0.728714 811 | 810 -84.6794 86.8198 -1.71889 0.0179748 -0.0107204 -0.6846 0.728618 812 | 811 -84.6102 85.6798 -1.71349 0.0178797 -0.0116888 -0.68451 0.728691 813 | 812 -84.5387 84.5401 -1.70422 0.0189816 -0.0125311 -0.683914 0.729208 814 | 813 -84.4601 83.3958 -1.69626 0.0198434 -0.0126013 -0.682961 0.730077 815 | 814 -84.3766 82.2679 -1.68699 0.02034 -0.0124548 -0.681719 0.731225 816 | 815 -84.291 81.1406 -1.67905 0.0200469 -0.0117672 -0.680657 0.732233 817 | 816 -84.2007 80.0117 -1.66925 0.0188607 -0.0113872 -0.679635 0.733219 818 | 817 -84.1076 78.8961 -1.65742 0.0175276 -0.0111395 -0.678642 0.734175 819 | 818 -84.0151 77.7819 -1.6493 0.0174074 -0.0111556 -0.677622 0.73512 820 | 819 -83.9132 76.6743 -1.63807 0.0182809 -0.0111002 -0.676903 0.735762 821 | 820 -83.8157 75.5572 -1.63198 0.0184415 -0.0107827 -0.676261 0.736352 822 | 821 -83.713 74.4359 -1.62321 0.0184937 -0.0103202 -0.675695 0.736877 823 | 822 -83.6124 73.3311 -1.6136 0.0188958 -0.010087 -0.675206 0.737318 824 | 823 -83.5078 72.2364 -1.60723 0.0183745 -0.00932071 -0.674842 0.737675 825 | 824 -83.4025 71.1396 -1.60118 0.0182673 -0.00892706 -0.674878 0.737649 826 | 825 -83.2975 70.0319 -1.59614 0.0170983 -0.00834283 -0.675166 0.737421 827 | 826 -83.1988 68.9376 -1.59153 0.0169831 -0.00841443 -0.675705 0.736928 828 | 827 -83.099 67.8507 -1.58866 0.0174135 -0.0088632 -0.676279 0.736386 829 | 828 -83.0109 66.7642 -1.5832 0.0182629 -0.00991121 -0.67712 0.73558 830 | 829 -82.9248 65.6719 -1.57345 0.0183995 -0.0108738 -0.677946 0.734801 831 | 830 -82.8391 64.5828 -1.5661 0.0191185 -0.0122448 -0.678784 0.733987 832 | 831 -82.7557 63.4937 -1.56016 0.020204 -0.0127784 -0.679557 0.733233 833 | 832 -82.6752 62.4014 -1.55111 0.0209922 -0.0123681 -0.680384 0.732451 834 | 833 -82.5889 61.3174 -1.5462 0.0212905 -0.011702 -0.68129 0.73161 835 | 834 -82.5063 60.2474 -1.54404 0.0209975 -0.0112068 -0.682094 0.730877 836 | 835 -82.4275 59.1794 -1.53819 0.0197086 -0.0108297 -0.682927 0.73014 837 | 836 -82.3533 58.0846 -1.53327 0.0187915 -0.0114973 -0.683654 0.729473 838 | 837 -82.2759 57.0051 -1.52366 0.0174569 -0.0121725 -0.684313 0.728878 839 | 838 -82.2046 55.9188 -1.51273 0.0171781 -0.0131361 -0.68488 0.728335 840 | 839 -82.1359 54.8463 -1.49811 0.0169424 -0.0132946 -0.685149 0.728084 841 | 840 -82.0706 53.7801 -1.49064 0.0177224 -0.0127348 -0.685341 0.727896 842 | 841 -82.0071 52.7082 -1.48063 0.0187301 -0.0120925 -0.685229 0.727986 843 | 842 -81.9304 51.6486 -1.46974 0.0184751 -0.0106687 -0.685092 0.728144 844 | 843 -81.8551 50.5734 -1.46614 0.0175541 -0.00904391 -0.684878 0.72839 845 | 844 -81.7754 49.5024 -1.45748 0.016311 -0.00783656 -0.684676 0.728623 846 | 845 -81.6959 48.4398 -1.45523 0.0148875 -0.00676715 -0.684529 0.728802 847 | 846 -81.6183 47.3716 -1.44929 0.013074 -0.00558706 -0.684436 0.728934 848 | 847 -81.542 46.3117 -1.44115 0.0123535 -0.00567391 -0.684282 0.72909 849 | 848 -81.4676 45.2628 -1.43564 0.0109196 -0.00548347 -0.684015 0.729366 850 | 849 -81.4029 44.2069 -1.41597 0.0102877 -0.00546474 -0.683726 0.729645 851 | 850 -81.3312 43.1537 -1.41758 0.0133074 -0.00546097 -0.683405 0.729898 852 | 851 -81.2587 42.0871 -1.4182 0.0164619 -0.0050781 -0.683175 0.730052 853 | 852 -81.1896 41.021 -1.41727 0.0175092 -0.00550383 -0.68273 0.730441 854 | 853 -81.1156 39.972 -1.40715 0.016561 -0.00739578 -0.682331 0.730818 855 | 854 -81.0449 38.9267 -1.40522 0.0148259 -0.00826826 -0.682118 0.731045 856 | 855 -80.966 37.8803 -1.40187 0.0145752 -0.00897815 -0.681992 0.731159 857 | 856 -80.8834 36.8441 -1.3913 0.0143682 -0.0091786 -0.681802 0.731338 858 | 857 -80.8094 35.7908 -1.38063 0.0147763 -0.0098603 -0.681692 0.731424 859 | 858 -80.7373 34.7425 -1.36725 0.0151049 -0.0115963 -0.681663 0.731419 860 | 859 -80.666 33.7134 -1.35147 0.0145676 -0.012962 -0.681797 0.731282 861 | 860 -80.5977 32.6765 -1.3368 0.0148412 -0.0136472 -0.681945 0.731126 862 | 861 -80.5231 31.6409 -1.32079 0.0162365 -0.0136917 -0.682195 0.730862 863 | 862 -80.4508 30.6143 -1.30883 0.0179123 -0.0126333 -0.682492 0.730564 864 | 863 -80.3799 29.5813 -1.29286 0.0185065 -0.0122717 -0.682792 0.730275 865 | 864 -80.3018 28.561 -1.28587 0.0181132 -0.0125102 -0.683164 0.729933 866 | 865 -80.2301 27.5442 -1.27024 0.0165697 -0.012014 -0.683605 0.729565 867 | 866 -80.1677 26.5426 -1.26371 0.0163688 -0.0114847 -0.684118 0.729097 868 | 867 -80.0961 25.5418 -1.25307 0.0168411 -0.0105844 -0.684481 0.72876 869 | 868 -80.0246 24.5308 -1.24594 0.0176066 -0.0104524 -0.684804 0.728439 870 | 869 -79.9672 23.5296 -1.23177 0.0179842 -0.010809 -0.685189 0.728063 871 | 870 -79.9041 22.5288 -1.22579 0.0180181 -0.0110314 -0.685422 0.72784 872 | 871 -79.8382 21.5319 -1.21624 0.0177155 -0.0105705 -0.685685 0.727606 873 | 872 -79.7757 20.5575 -1.21425 0.0176626 -0.0095398 -0.685987 0.727337 874 | 873 -79.7159 19.5837 -1.20186 0.0174932 -0.00889049 -0.686289 0.727064 875 | 874 -79.6553 18.6348 -1.19329 0.0174115 -0.00846771 -0.686658 0.726723 876 | 875 -79.5917 17.6919 -1.18471 0.0176885 -0.0077701 -0.686808 0.726582 877 | 876 -79.5304 16.7653 -1.18032 0.0180435 -0.00721055 -0.686946 0.726449 878 | 877 -79.4815 15.8761 -1.17353 0.018234 -0.00718369 -0.68668 0.726696 879 | 878 -79.4309 15.0226 -1.16698 0.0177901 -0.00732112 -0.685765 0.727569 880 | 879 -79.3728 14.1782 -1.15856 0.0174842 -0.0077074 -0.684623 0.728646 881 | 880 -79.3068 13.3554 -1.15259 0.0170213 -0.00748855 -0.683117 0.730072 882 | 881 -79.2366 12.5431 -1.14734 0.0158346 -0.00669636 -0.681526 0.731592 883 | 882 -79.1736 11.7571 -1.13632 0.01537 -0.00711891 -0.679694 0.7333 884 | 883 -79.1085 10.9951 -1.12965 0.0150357 -0.00793071 -0.677038 0.735751 885 | 884 -79.0416 10.2675 -1.12109 0.0148862 -0.00918016 -0.673812 0.738695 886 | 885 -78.9629 9.5493 -1.10728 0.0148218 -0.0103943 -0.669603 0.742498 887 | 886 -78.8764 8.85681 -1.09774 0.0146579 -0.0105544 -0.665051 0.746579 888 | 887 -78.7815 8.18307 -1.08352 0.0145443 -0.0108226 -0.660369 0.750722 889 | 888 -78.6868 7.51668 -1.07349 0.0150349 -0.0110264 -0.655084 0.755326 890 | 889 -78.5917 6.90585 -1.05683 0.0160787 -0.0109011 -0.649259 0.760319 891 | 890 -78.4739 6.30034 -1.04257 0.015678 -0.0106207 -0.642758 0.765835 892 | 891 -78.3503 5.72388 -1.03354 0.0140682 -0.0101137 -0.6356 0.771824 893 | 892 -78.2159 5.15576 -1.02125 0.0124779 -0.00929492 -0.627752 0.778258 894 | 893 -78.0719 4.61489 -1.00768 0.0129393 -0.00986168 -0.61921 0.785057 895 | 894 -77.9181 4.08074 -0.992413 0.0128557 -0.00952626 -0.610233 0.79206 896 | 895 -77.7572 3.55965 -0.985212 0.0120595 -0.00889877 -0.600589 0.799418 897 | 896 -77.5766 3.04649 -0.973167 0.011244 -0.00879043 -0.589804 0.807421 898 | 897 -77.3913 2.55993 -0.964726 0.0100901 -0.00939125 -0.577464 0.8163 899 | 898 -77.1861 2.07369 -0.951862 0.00918652 -0.0107884 -0.563203 0.826197 900 | 899 -76.9708 1.611 -0.942671 0.00876004 -0.0122855 -0.547318 0.836789 901 | 900 -76.744 1.17352 -0.929944 0.010101 -0.0132772 -0.529042 0.848432 902 | 901 -76.483 0.732621 -0.909048 0.0118561 -0.0130377 -0.50805 0.861148 903 | 902 -76.2068 0.328354 -0.888654 0.0111777 -0.0117943 -0.485611 0.874024 904 | 903 -75.9232 -0.0308845 -0.881228 0.00876035 -0.0112498 -0.462889 0.886301 905 | 904 -75.5934 -0.409674 -0.868872 0.00684366 -0.011561 -0.439816 0.897988 906 | 905 -75.2625 -0.756232 -0.859002 0.00697411 -0.0134474 -0.415987 0.909245 907 | 906 -74.9506 -1.06756 -0.821131 0.00811018 -0.0146051 -0.39202 0.919805 908 | 907 -74.5851 -1.3824 -0.806776 0.00630266 -0.0133674 -0.368315 0.929584 909 | 908 -74.2148 -1.63501 -0.803101 0.00246951 -0.0109625 -0.344697 0.938647 910 | 909 -73.8078 -1.91433 -0.792886 -0.000392884 -0.0085194 -0.320268 0.947289 911 | 910 -73.4053 -2.1571 -0.778851 0.000339102 -0.00609506 -0.295672 0.95527 912 | 911 -73.0132 -2.36729 -0.763115 0.00198542 -0.00292624 -0.271235 0.962507 913 | 912 -72.5639 -2.5882 -0.738531 0.0011176 0.00067914 -0.246475 0.969148 914 | 913 -72.1378 -2.73026 -0.747789 -0.00314003 0.00403849 -0.22212 0.975006 915 | 914 -71.6632 -2.90897 -0.743137 -0.0051205 0.00577184 -0.197651 0.980242 916 | 915 -71.2135 -3.03875 -0.740182 -0.00574373 0.00495562 -0.173688 0.984772 917 | 916 -70.7831 -3.14288 -0.72942 -0.0054931 0.00399251 -0.151769 0.988393 918 | 917 -70.2932 -3.27094 -0.71882 -0.00590086 0.00354567 -0.131549 0.991286 919 | 918 -69.8175 -3.34949 -0.725388 -0.0082414 0.00351407 -0.113369 0.993513 920 | 919 -69.3161 -3.42498 -0.737866 -0.0110865 0.00338997 -0.096124 0.995302 921 | 920 -68.8154 -3.48596 -0.733005 -0.012061 0.00306109 -0.0819126 0.996562 922 | 921 -68.3108 -3.55363 -0.719481 -0.0123959 0.00369005 -0.0708024 0.997407 923 | 922 -67.7777 -3.60853 -0.729531 -0.0124689 0.00385054 -0.060228 0.998099 924 | 923 -67.2631 -3.6539 -0.714462 -0.0114535 0.00336225 -0.0512079 0.998617 925 | 924 -66.7167 -3.69289 -0.713304 -0.0111542 0.00277449 -0.0434732 0.998988 926 | 925 -66.1481 -3.72848 -0.715382 -0.0115121 0.00207761 -0.0364508 0.999267 927 | 926 -65.5825 -3.75741 -0.715937 -0.0117425 0.00175026 -0.0296128 0.999491 928 | 927 -64.9942 -3.78062 -0.710801 -0.0115651 0.00150255 -0.0227411 0.999673 929 | 928 -64.3888 -3.79374 -0.712725 -0.0113894 0.00134075 -0.0159205 0.999807 930 | 929 -63.7693 -3.80592 -0.707612 -0.009738 0.00153268 -0.00882593 0.999912 931 | 930 -63.1247 -3.79997 -0.698706 -0.00990081 0.00116123 -0.00244987 0.999947 932 | 931 -62.4735 -3.78301 -0.6967 -0.0101755 0.000487274 0.00270902 0.999944 933 | 932 -61.8255 -3.76666 -0.694561 -0.0110778 -0.000194394 0.00681384 0.999915 934 | 933 -61.1312 -3.74874 -0.691005 -0.0114311 -0.000622185 0.00996021 0.999885 935 | 934 -60.4201 -3.73324 -0.690187 -0.0111107 -0.000979183 0.0120476 0.999865 936 | 935 -59.7019 -3.70473 -0.679223 -0.0110685 -0.00110323 0.0135005 0.999847 937 | 936 -58.9611 -3.67974 -0.673833 -0.0104607 -0.00066673 0.0148507 0.999835 938 | 937 -58.2055 -3.65084 -0.662611 -0.0100826 0.000167651 0.0162629 0.999817 939 | 938 -57.4463 -3.64275 -0.656415 -0.00887617 0.00120055 0.0176178 0.999805 940 | 939 -56.688 -3.59642 -0.647161 -0.00935186 0.00237511 0.0193357 0.999766 941 | 940 -55.9285 -3.56654 -0.642594 -0.00862915 0.00357396 0.0208106 0.99974 942 | 941 -55.1699 -3.51998 -0.639245 -0.00761276 0.00443517 0.0225955 0.999706 943 | 942 -54.4065 -3.47779 -0.631197 -0.0066535 0.00483596 0.0242265 0.999673 944 | 943 -53.6394 -3.4432 -0.627564 -0.00521124 0.00497968 0.0259214 0.999638 945 | 944 -52.8757 -3.39285 -0.62356 -0.00518887 0.00479143 0.027896 0.999586 946 | 945 -52.1124 -3.35292 -0.617891 -0.00529254 0.00471258 0.0292886 0.999546 947 | 946 -51.3525 -3.28928 -0.61072 -0.00516644 0.00470775 0.0309352 0.999497 948 | 947 -50.5872 -3.23808 -0.612283 -0.0046725 0.00487074 0.0318324 0.99947 949 | 948 -49.8157 -3.18071 -0.603638 -0.00519003 0.00463998 0.0324333 0.99945 950 | 949 -49.0551 -3.12481 -0.601664 -0.00635335 0.00466798 0.0328782 0.999428 951 | 950 -48.2904 -3.06835 -0.59378 -0.00601195 0.00461712 0.0328585 0.999431 952 | 951 -47.5224 -3.01996 -0.589546 -0.00586293 0.00499418 0.0332116 0.999419 953 | 952 -46.7606 -2.96225 -0.583708 -0.00594509 0.0053921 0.0333484 0.999412 954 | 953 -45.9986 -2.91198 -0.583372 -0.00657354 0.00599889 0.0333096 0.999405 955 | 954 -45.2448 -2.86007 -0.579034 -0.00626617 0.00634154 0.0333446 0.999404 956 | 955 -44.4865 -2.80497 -0.571449 -0.0059847 0.00642143 0.0334708 0.999401 957 | 956 -43.7305 -2.74762 -0.574527 -0.00619743 0.00640083 0.0333779 0.999403 958 | 957 -42.9903 -2.68803 -0.572419 -0.00584856 0.00599644 0.0329964 0.99942 959 | 958 -42.2519 -2.64145 -0.566962 -0.00537633 0.00568501 0.0320842 0.999455 960 | 959 -41.5165 -2.59765 -0.565496 -0.00494682 0.00565299 0.0314114 0.999478 961 | 960 -40.782 -2.5405 -0.559655 -0.00515224 0.00552223 0.030834 0.999496 962 | 961 -40.0668 -2.50372 -0.557589 -0.00474649 0.00606344 0.0303171 0.999511 963 | 962 -39.3485 -2.4596 -0.544119 -0.00386024 0.00686788 0.0296231 0.99953 964 | 963 -38.6368 -2.4174 -0.555707 -0.00435937 0.00780463 0.0291196 0.999536 965 | 964 -37.9405 -2.36815 -0.55033 -0.00484763 0.00781789 0.0285211 0.999551 966 | 965 -37.2616 -2.32951 -0.536027 -0.00409926 0.00692213 0.028196 0.99957 967 | 966 -36.6006 -2.29461 -0.538669 -0.00292824 0.00553136 0.0280337 0.999587 968 | 967 -35.9528 -2.24767 -0.527793 -0.00519605 0.00340245 0.0275758 0.9996 969 | 968 -35.2916 -2.20081 -0.530536 -0.00624648 0.00275446 0.0272954 0.999604 970 | 969 -34.6443 -2.16478 -0.523045 -0.00653856 0.00259009 0.0273135 0.999602 971 | 970 -34.0024 -2.12931 -0.514667 -0.00628991 0.00231969 0.0269045 0.999616 972 | 971 -33.3625 -2.08843 -0.507096 -0.00649744 0.00197123 0.0267029 0.99962 973 | 972 -32.7307 -2.0523 -0.499194 -0.00802749 0.00137962 0.0266567 0.999611 974 | 973 -32.1096 -2.01395 -0.48999 -0.00906316 0.000930168 0.0265104 0.999607 975 | 974 -31.4827 -1.97283 -0.485144 -0.00906128 0.000883471 0.0265811 0.999605 976 | 975 -30.8446 -1.93231 -0.472212 -0.00885632 0.00107894 0.0268837 0.999599 977 | 976 -30.2171 -1.89706 -0.459222 -0.00882919 0.00134374 0.027363 0.999586 978 | 977 -29.6104 -1.86331 -0.451883 -0.00821153 0.00156569 0.0276536 0.999583 979 | 978 -29.0048 -1.82419 -0.443599 -0.00729698 0.00117775 0.0281983 0.999575 980 | 979 -28.3862 -1.78386 -0.428652 -0.00734261 0.000551574 0.0291434 0.999548 981 | 980 -27.7732 -1.73902 -0.418751 -0.00772333 0.000111487 0.0298965 0.999523 982 | 981 -27.1756 -1.70989 -0.413605 -0.00720917 -0.000101191 0.0307206 0.999502 983 | 982 -26.5871 -1.66789 -0.406862 -0.00693007 -1.61363e-05 0.0317861 0.999471 984 | 983 -25.9762 -1.61641 -0.395056 -0.00640112 -9.00132e-05 0.0327737 0.999442 985 | 984 -25.3675 -1.56388 -0.384158 -0.00568554 1.71234e-05 0.0338511 0.999411 986 | 985 -24.7703 -1.53238 -0.368805 -0.00599827 0.000496092 0.0347847 0.999377 987 | 986 -24.1868 -1.48723 -0.356197 -0.00681593 0.000792642 0.0358383 0.999334 988 | 987 -23.604 -1.44262 -0.350169 -0.00676863 0.00124015 0.0368362 0.999298 989 | 988 -23.0188 -1.38851 -0.344236 -0.00673721 0.00173446 0.0375339 0.999271 990 | 989 -22.4464 -1.34405 -0.33114 -0.00691044 0.00201227 0.038124 0.999247 991 | 990 -21.8883 -1.30696 -0.328934 -0.00639638 0.00218739 0.0381677 0.999248 992 | 991 -21.3456 -1.26474 -0.318418 -0.00699531 0.00216452 0.0382884 0.99924 993 | 992 -20.809 -1.21507 -0.311983 -0.008136 0.00224002 0.0381754 0.999235 994 | 993 -20.2748 -1.16898 -0.306333 -0.00834372 0.00221635 0.0373821 0.999264 995 | 994 -19.7619 -1.13538 -0.296912 -0.00847492 0.00189514 0.0366785 0.999289 996 | 995 -19.2536 -1.09429 -0.286361 -0.00751894 0.00194199 0.0359612 0.999323 997 | 996 -18.7561 -1.04813 -0.279551 -0.00682738 0.00187053 0.0352568 0.999353 998 | 997 -18.2637 -1.0188 -0.276405 -0.0064162 0.00152085 0.0344483 0.999385 999 | 998 -17.7849 -0.980982 -0.268737 -0.00679974 0.00137486 0.0339072 0.999401 1000 | 999 -17.3094 -0.938667 -0.261716 -0.00737735 0.00135114 0.0336105 0.999407 1001 | 1000 -16.8483 -0.906979 -0.259858 -0.00753436 0.00130607 0.0329701 0.999427 1002 | 1001 -16.403 -0.886839 -0.250789 -0.00714497 0.00159484 0.032399 0.999448 1003 | 1002 -15.974 -0.862726 -0.235681 -0.0074162 0.00177031 0.0318934 0.999462 1004 | 1003 -15.5533 -0.836659 -0.230767 -0.00680998 0.002191 0.0313996 0.999481 1005 | 1004 -15.1865 -0.814601 -0.23049 -0.0071129 0.00270984 0.0311387 0.999486 1006 | 1005 -14.8145 -0.784541 -0.223999 -0.00763229 0.00312033 0.0305519 0.999499 1007 | 1006 -14.4585 -0.75165 -0.217977 -0.0075554 0.00314808 0.03018 0.999511 1008 | 1007 -14.1368 -0.738332 -0.21121 -0.00708365 0.00289264 0.0298212 0.999526 1009 | 1008 -13.8315 -0.715886 -0.207106 -0.00691842 0.00259096 0.0294135 0.99954 1010 | 1009 -13.5468 -0.7023 -0.203498 -0.00664232 0.00241257 0.0292097 0.999548 1011 | 1010 -13.2643 -0.679522 -0.200357 -0.0066191 0.00209674 0.0289222 0.999558 1012 | 1011 -12.9978 -0.660051 -0.19511 -0.00693848 0.00168457 0.0287719 0.999561 1013 | 1012 -12.7433 -0.639841 -0.190204 -0.00633381 0.00071327 0.0285617 0.999572 1014 | 1013 -12.4847 -0.624685 -0.186304 -0.00643895 3.86443e-05 0.0283356 0.999578 1015 | 1014 -12.2361 -0.60711 -0.182825 -0.0065514 -0.000172699 0.0280801 0.999584 1016 | 1015 -11.98 -0.598452 -0.18226 -0.00642807 0.000143637 0.028013 0.999587 1017 | 1016 -11.723 -0.584816 -0.180758 -0.00639145 0.000324956 0.027929 0.999589 1018 | 1017 -11.4692 -0.569129 -0.172161 -0.00632956 0.0005726 0.0278747 0.999591 1019 | 1018 -11.2175 -0.554326 -0.169387 -0.00538012 0.000559029 0.0275959 0.999605 1020 | 1019 -10.9673 -0.537894 -0.166829 -0.00575818 0.000667799 0.0279598 0.999592 1021 | 1020 -10.7215 -0.523161 -0.166287 -0.00538327 0.000681223 0.0278253 0.999598 1022 | 1021 -10.472 -0.5136 -0.160972 -0.00495504 0.00067735 0.028445 0.999583 1023 | 1022 -10.226 -0.500265 -0.15743 -0.00384371 0.000705418 0.0298877 0.999546 1024 | 1023 -9.97538 -0.480546 -0.159502 -0.00332286 0.00060393 0.0320789 0.99948 1025 | 1024 -9.7381 -0.458915 -0.151177 -0.00376161 0.000707804 0.0352155 0.999372 1026 | 1025 -9.50168 -0.427333 -0.145087 -0.00419751 0.000377223 0.0388365 0.999237 1027 | 1026 -9.26718 -0.408568 -0.138665 -0.00506873 0.000339012 0.0427968 0.999071 1028 | 1027 -9.03632 -0.364289 -0.136239 -0.00610404 0.00034588 0.0457041 0.998936 1029 | 1028 -8.8039 -0.338068 -0.134795 -0.00698534 0.000151405 0.0479888 0.998823 1030 | 1029 -8.56256 -0.31131 -0.130455 -0.00633115 6.42073e-06 0.0504054 0.998709 1031 | 1030 -8.33025 -0.285839 -0.123049 -0.00621795 -0.000137734 0.0528872 0.998581 1032 | 1031 -8.09649 -0.252246 -0.121856 -0.00634452 -0.000168884 0.0548961 0.998472 1033 | 1032 -7.8721 -0.219525 -0.119841 -0.00779457 -0.000220148 0.0560616 0.998397 1034 | 1033 -7.63354 -0.181208 -0.119057 -0.009075 -0.00049861 0.0563796 0.998368 1035 | 1034 -7.40371 -0.155518 -0.111386 -0.00922395 -0.000531567 0.0559712 0.99839 1036 | 1035 -7.17816 -0.13053 -0.108216 -0.00862741 -0.000508369 0.0552578 0.998435 1037 | 1036 -6.95244 -0.108222 -0.1028 -0.00835279 -0.00038562 0.0544089 0.998484 1038 | 1037 -6.72301 -0.081142 -0.0988356 -0.00840039 -0.000151989 0.0533231 0.998542 1039 | 1038 -6.50126 -0.0555819 -0.0974179 -0.00820384 -0.000239287 0.052067 0.99861 1040 | 1039 -6.27489 -0.0387675 -0.0942323 -0.00854831 -0.000402968 0.0507943 0.998672 1041 | 1040 -6.0552 -0.0136285 -0.092344 -0.00854831 -0.000549809 0.0493577 0.998744 1042 | 1041 -5.83552 0.00391073 -0.0856038 -0.00843025 -0.000527059 0.0477925 0.998822 1043 | 1042 -5.61626 0.0278132 -0.0795265 -0.00819975 -0.000362169 0.0458667 0.998914 1044 | 1043 -5.39164 0.0425367 -0.0782037 -0.00792163 -0.000525544 0.0436318 0.999016 1045 | 1044 -5.16457 0.0635456 -0.0771712 -0.00795019 -0.000874796 0.0417437 0.999096 1046 | 1045 -4.94099 0.0853742 -0.0693561 -0.00842098 -0.00164807 0.0397385 0.999173 1047 | 1046 -4.70478 0.101254 -0.067842 -0.00768945 -0.00242328 0.0374138 0.999267 1048 | 1047 -4.45326 0.113742 -0.0644795 -0.00730371 -0.00263062 0.0350416 0.999356 1049 | 1048 -4.18453 0.132139 -0.0592775 -0.0070142 -0.00247265 0.0326924 0.999438 1050 | 1049 -3.90661 0.145228 -0.0549897 -0.00686887 -0.00221439 0.0303903 0.999512 1051 | 1050 -3.60955 0.153043 -0.0521303 -0.00568654 -0.00180368 0.027673 0.999599 1052 | 1051 -3.30413 0.162228 -0.0443121 -0.00493316 -0.0010364 0.025208 0.99967 1053 | 1052 -2.99467 0.170441 -0.038993 -0.00499831 -0.000511601 0.0227638 0.999728 1054 | 1053 -2.67162 0.185462 -0.0350548 -0.00479389 -5.55919e-05 0.0205377 0.999778 1055 | 1054 -2.34067 0.195841 -0.0326865 -0.00504125 0.00021344 0.0183326 0.999819 1056 | 1055 -2.00626 0.209183 -0.0317306 -0.00466202 0.000557643 0.0163686 0.999855 1057 | 1056 -1.65799 0.216049 -0.0260108 -0.00433242 0.00125957 0.0142002 0.999889 1058 | 1057 -1.30813 0.214553 -0.0219733 -0.00425736 0.00133118 0.0123072 0.999914 1059 | 1058 -0.947265 0.223324 -0.00632015 -0.0036719 0.000504155 0.0110303 0.999932 1060 | 1059 -0.569052 0.230836 -0.00326628 -0.00295263 -0.000438128 0.0103801 0.999942 1061 | 1060 -0.19063 0.244137 0.00295074 -0.00328619 -0.001472 0.00968681 0.999947 1062 | 1061 0.19132 0.259209 0.0092052 -0.0043671 -0.0016382 0.00825993 0.999955 1063 | 1062 0.586414 0.2753 0.00292071 -0.00657432 -0.000953203 0.00582805 0.999961 1064 | 1063 1.00101 0.279134 -0.0019305 -0.00574246 -0.000626217 0.0016223 0.999982 1065 | 1064 1.41946 0.266795 0.0130795 -0.00142272 -0.000577011 -0.0023681 0.999996 1066 | 1065 1.83359 0.240355 0.0316601 0.00230199 -0.00177257 -0.00406357 0.999988 1067 | 1066 2.23056 0.222629 0.0471641 0.00398574 -0.00344244 -0.00252462 0.999983 1068 | 1067 2.60529 0.239859 0.0512246 0.00244968 -0.00493326 0.00318654 0.99998 1069 | 1068 2.97694 0.279231 0.0623828 -0.000475862 -0.0064416 0.011732 0.99991 1070 | 1069 3.34185 0.320091 0.0567189 -0.00357248 -0.00807734 0.0204823 0.999751 1071 | 1070 3.71267 0.355758 0.0596826 -0.00386861 -0.00918776 0.0300863 0.999498 1072 | 1071 4.07942 0.394206 0.0736975 -0.00240796 -0.00898585 0.0415035 0.999095 1073 | 1072 4.43634 0.436459 0.0982435 -0.00236998 -0.00607382 0.0537647 0.998532 1074 | 1073 4.79745 0.488392 0.105735 -0.00414061 -0.00292487 0.0664796 0.997775 1075 | 1074 5.14837 0.565578 0.114343 -0.00657313 -0.00113073 0.0798221 0.996787 1076 | 1075 5.49898 0.66396 0.115488 -0.00768323 -0.000377951 0.0929406 0.995642 1077 | 1076 5.84645 0.758487 0.114709 -0.0080443 0.000971926 0.104916 0.994448 1078 | 1077 6.17791 0.837299 0.12772 -0.00832879 0.00250419 0.115331 0.993289 1079 | 1078 6.51022 0.923878 0.13453 -0.0103367 0.00397932 0.122846 0.992364 1080 | 1079 6.84451 1.02352 0.133978 -0.0132274 0.00557068 0.126949 0.991805 1081 | 1080 7.17974 1.12577 0.136557 -0.0151648 0.00661158 0.127956 0.991642 1082 | 1081 7.51132 1.21343 0.134153 -0.0160268 0.00673416 0.125574 0.991932 1083 | 1082 7.84897 1.301 0.135224 -0.0152084 0.00673484 0.121504 0.992452 1084 | 1083 8.16999 1.36372 0.136414 -0.0125032 0.008386 0.117167 0.992998 1085 | 1084 8.46049 1.41172 0.146448 -0.0112195 0.00979994 0.112285 0.993564 1086 | 1085 8.71036 1.46505 0.140179 -0.0114879 0.0103181 0.107144 0.994124 1087 | 1086 8.91717 1.5084 0.142961 -0.0121566 0.0103914 0.102159 0.99464 1088 | 1087 9.08025 1.53979 0.136843 -0.0119489 0.00981461 0.0972632 0.995139 1089 | 1088 9.19943 1.55664 0.145456 -0.0105927 0.00933633 0.0934101 0.995528 1090 | 1089 9.2832 1.5625 0.146893 -0.00979 0.0088566 0.0906585 0.995795 1091 | 1090 9.34129 1.56494 0.142153 -0.00985095 0.00858038 0.0887503 0.995968 1092 | 1091 9.37611 1.57436 0.139983 -0.0102548 0.00793474 0.0878421 0.99605 1093 | 1092 9.37629 1.57344 0.139702 -0.01034 0.00759834 0.0878683 0.996049 1094 | 1093 9.34959 1.56588 0.142915 -0.0105721 0.00675662 0.0880479 0.996037 1095 | 1094 9.32453 1.56391 0.148415 -0.0106209 0.00426567 0.0880295 0.996052 1096 | 1095 9.30762 1.56674 0.147361 -0.0105525 0.00251291 0.0882147 0.996042 1097 | 1096 9.30475 1.56615 0.145664 -0.0103975 0.00286915 0.0881695 0.996047 1098 | 1097 9.31033 1.56293 0.145819 -0.0102928 0.00347259 0.0881311 0.99605 1099 | 1098 9.31475 1.56418 0.148179 -0.0102414 0.00364473 0.0881591 0.996047 1100 | 1099 9.31761 1.56272 0.145875 -0.0104212 0.00398374 0.0880806 0.996051 1101 | 1100 9.31749 1.56443 0.148736 -0.0104536 0.00395826 0.0880163 0.996056 1102 | -------------------------------------------------------------------------------- /rviz_cfg/loop.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 0 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /Grid1 9 | - /Axes1 10 | - /PointCloud21 11 | - /PointCloud22 12 | - /PointCloud23 13 | - /PointCloud24 14 | - /MarkerArray1 15 | - /Odometry1 16 | - /PointCloud25 17 | - /PointCloud26 18 | Splitter Ratio: 0.5243902206420898 19 | Tree Height: 700 20 | - Class: rviz/Selection 21 | Name: Selection 22 | - Class: rviz/Tool Properties 23 | Expanded: 24 | - /2D Pose Estimate1 25 | - /2D Nav Goal1 26 | - /Publish Point1 27 | Name: Tool Properties 28 | Splitter Ratio: 0.5886790156364441 29 | - Class: rviz/Views 30 | Expanded: 31 | - /Current View1 32 | Name: Views 33 | Splitter Ratio: 0.5 34 | - Class: rviz/Time 35 | Name: Time 36 | SyncMode: 0 37 | SyncSource: PointCloud2 38 | Preferences: 39 | PromptSaveOnExit: true 40 | Toolbars: 41 | toolButtonStyle: 2 42 | Visualization Manager: 43 | Class: "" 44 | Displays: 45 | - Alpha: 1 46 | Cell Size: 1 47 | Class: rviz/Grid 48 | Color: 160; 160; 164 49 | Enabled: false 50 | Line Style: 51 | Line Width: 0.029999999329447746 52 | Value: Lines 53 | Name: Grid 54 | Normal Cell Count: 0 55 | Offset: 56 | X: 50 57 | Y: 50 58 | Z: 0 59 | Plane: XY 60 | Plane Cell Count: 10000 61 | Reference Frame: 62 | Value: false 63 | - Alpha: 1 64 | Class: rviz/Axes 65 | Enabled: true 66 | Length: 0.699999988079071 67 | Name: Axes 68 | Radius: 0.05999999865889549 69 | Reference Frame: 70 | Show Trail: false 71 | Value: true 72 | - Alpha: 0.5 73 | Autocompute Intensity Bounds: true 74 | Autocompute Value Bounds: 75 | Max Value: 10 76 | Min Value: -10 77 | Value: true 78 | Axis: Z 79 | Channel Name: intensity 80 | Class: rviz/PointCloud2 81 | Color: 255; 255; 255 82 | Color Transformer: FlatColor 83 | Decay Time: 0 84 | Enabled: true 85 | Invert Rainbow: false 86 | Max Color: 255; 255; 255 87 | Min Color: 0; 0; 0 88 | Name: PointCloud2 89 | Position Transformer: XYZ 90 | Queue Size: 10 91 | Selectable: true 92 | Size (Pixels): 3 93 | Size (m): 0.05000000074505806 94 | Style: Points 95 | Topic: /cloud_current 96 | Unreliable: false 97 | Use Fixed Frame: true 98 | Use rainbow: true 99 | Value: true 100 | - Class: rviz/Marker 101 | Enabled: false 102 | Marker Topic: /planner_normal 103 | Name: Marker 104 | Namespaces: 105 | {} 106 | Queue Size: 1000 107 | Value: false 108 | - Alpha: 0.800000011920929 109 | Autocompute Intensity Bounds: true 110 | Autocompute Value Bounds: 111 | Max Value: 10 112 | Min Value: -10 113 | Value: true 114 | Axis: Z 115 | Channel Name: intensity 116 | Class: rviz/PointCloud2 117 | Color: 255; 255; 255 118 | Color Transformer: FlatColor 119 | Decay Time: 0 120 | Enabled: true 121 | Invert Rainbow: false 122 | Max Color: 255; 255; 255 123 | Min Color: 0; 0; 0 124 | Name: PointCloud2 125 | Position Transformer: XYZ 126 | Queue Size: 10 127 | Selectable: true 128 | Size (Pixels): 3 129 | Size (m): 0.5 130 | Style: Flat Squares 131 | Topic: /cloud_key_points 132 | Unreliable: false 133 | Use Fixed Frame: true 134 | Use rainbow: true 135 | Value: true 136 | - Alpha: 0.5 137 | Autocompute Intensity Bounds: true 138 | Autocompute Value Bounds: 139 | Max Value: 10 140 | Min Value: -10 141 | Value: true 142 | Axis: Z 143 | Channel Name: intensity 144 | Class: rviz/PointCloud2 145 | Color: 138; 226; 52 146 | Color Transformer: RGB8 147 | Decay Time: 0 148 | Enabled: true 149 | Invert Rainbow: false 150 | Max Color: 255; 255; 255 151 | Min Color: 0; 0; 0 152 | Name: PointCloud2 153 | Position Transformer: XYZ 154 | Queue Size: 10 155 | Selectable: true 156 | Size (Pixels): 3 157 | Size (m): 0.05000000074505806 158 | Style: Points 159 | Topic: /cloud_matched 160 | Unreliable: false 161 | Use Fixed Frame: true 162 | Use rainbow: true 163 | Value: true 164 | - Alpha: 0.800000011920929 165 | Autocompute Intensity Bounds: true 166 | Autocompute Value Bounds: 167 | Max Value: 10 168 | Min Value: -10 169 | Value: true 170 | Axis: Z 171 | Channel Name: intensity 172 | Class: rviz/PointCloud2 173 | Color: 138; 226; 52 174 | Color Transformer: FlatColor 175 | Decay Time: 0 176 | Enabled: true 177 | Invert Rainbow: false 178 | Max Color: 255; 255; 255 179 | Min Color: 0; 0; 0 180 | Name: PointCloud2 181 | Position Transformer: XYZ 182 | Queue Size: 10 183 | Selectable: true 184 | Size (Pixels): 3 185 | Size (m): 0.5 186 | Style: Flat Squares 187 | Topic: /cloud_matched_key_points 188 | Unreliable: false 189 | Use Fixed Frame: true 190 | Use rainbow: true 191 | Value: true 192 | - Class: rviz/MarkerArray 193 | Enabled: true 194 | Marker Topic: /descriptor_line 195 | Name: MarkerArray 196 | Namespaces: 197 | lines: true 198 | Queue Size: 100 199 | Value: true 200 | - Angle Tolerance: 0.10000000149011612 201 | Class: rviz/Odometry 202 | Covariance: 203 | Orientation: 204 | Alpha: 0.5 205 | Color: 255; 255; 127 206 | Color Style: Unique 207 | Frame: Local 208 | Offset: 1 209 | Scale: 1 210 | Value: true 211 | Position: 212 | Alpha: 0.30000001192092896 213 | Color: 204; 51; 204 214 | Scale: 1 215 | Value: true 216 | Value: true 217 | Enabled: true 218 | Keep: 100000 219 | Name: Odometry 220 | Position Tolerance: 0.10000000149011612 221 | Queue Size: 10 222 | Shape: 223 | Alpha: 1 224 | Axes Length: 1 225 | Axes Radius: 0.10000000149011612 226 | Color: 255; 25; 0 227 | Head Length: 0.30000001192092896 228 | Head Radius: 0.10000000149011612 229 | Shaft Length: 1 230 | Shaft Radius: 0.05000000074505806 231 | Value: Axes 232 | Topic: /aft_mapped_to_init 233 | Unreliable: false 234 | Value: true 235 | - Alpha: 1 236 | Autocompute Intensity Bounds: true 237 | Autocompute Value Bounds: 238 | Max Value: 10 239 | Min Value: -10 240 | Value: true 241 | Axis: Z 242 | Channel Name: intensity 243 | Class: rviz/PointCloud2 244 | Color: 255; 255; 255 245 | Color Transformer: "" 246 | Decay Time: 10000 247 | Enabled: true 248 | Invert Rainbow: false 249 | Max Color: 255; 255; 255 250 | Min Color: 0; 0; 0 251 | Name: PointCloud2 252 | Position Transformer: "" 253 | Queue Size: 10 254 | Selectable: true 255 | Size (Pixels): 3 256 | Size (m): 0.009999999776482582 257 | Style: Flat Squares 258 | Topic: /cloud_correct 259 | Unreliable: false 260 | Use Fixed Frame: true 261 | Use rainbow: true 262 | Value: true 263 | - Alpha: 1 264 | Autocompute Intensity Bounds: true 265 | Autocompute Value Bounds: 266 | Max Value: 10 267 | Min Value: -10 268 | Value: true 269 | Axis: Z 270 | Channel Name: intensity 271 | Class: rviz/PointCloud2 272 | Color: 255; 255; 255 273 | Color Transformer: Intensity 274 | Decay Time: 0 275 | Enabled: true 276 | Invert Rainbow: false 277 | Max Color: 255; 255; 255 278 | Min Color: 0; 0; 0 279 | Name: PointCloud2 280 | Position Transformer: XYZ 281 | Queue Size: 10 282 | Selectable: true 283 | Size (Pixels): 3 284 | Size (m): 0.009999999776482582 285 | Style: Flat Squares 286 | Topic: /cloud_registered 287 | Unreliable: false 288 | Use Fixed Frame: true 289 | Use rainbow: true 290 | Value: true 291 | - Class: rviz/MarkerArray 292 | Enabled: true 293 | Marker Topic: /loop_status 294 | Name: MarkerArray 295 | Namespaces: 296 | colored_path: true 297 | Queue Size: 100 298 | Value: true 299 | Enabled: true 300 | Global Options: 301 | Background Color: 0; 0; 0 302 | Default Light: true 303 | Fixed Frame: camera_init 304 | Frame Rate: 10 305 | Name: root 306 | Tools: 307 | - Class: rviz/Interact 308 | Hide Inactive Objects: true 309 | - Class: rviz/MoveCamera 310 | - Class: rviz/Select 311 | - Class: rviz/FocusCamera 312 | - Class: rviz/Measure 313 | - Class: rviz/SetInitialPose 314 | Theta std deviation: 0.2617993950843811 315 | Topic: /initialpose 316 | X std deviation: 0.5 317 | Y std deviation: 0.5 318 | - Class: rviz/SetGoal 319 | Topic: /move_base_simple/goal 320 | - Class: rviz/PublishPoint 321 | Single click: true 322 | Topic: /clicked_point 323 | Value: true 324 | Views: 325 | Current: 326 | Class: rviz/Orbit 327 | Distance: 776.4468383789062 328 | Enable Stereo Rendering: 329 | Stereo Eye Separation: 0.05999999865889549 330 | Stereo Focal Distance: 1 331 | Swap Stereo Eyes: false 332 | Value: false 333 | Field of View: 0.7853981852531433 334 | Focal Point: 335 | X: -4.092164516448975 336 | Y: 84.40666961669922 337 | Z: 0.0029877377673983574 338 | Focal Shape Fixed Size: false 339 | Focal Shape Size: 0.05000000074505806 340 | Invert Z Axis: false 341 | Name: Current View 342 | Near Clip Distance: 0.009999999776482582 343 | Pitch: 1.5697963237762451 344 | Target Frame: 345 | Yaw: 3.225398063659668 346 | Saved: 347 | - Class: rviz/Orbit 348 | Distance: 149.19589233398438 349 | Enable Stereo Rendering: 350 | Stereo Eye Separation: 0.05999999865889549 351 | Stereo Focal Distance: 1 352 | Swap Stereo Eyes: false 353 | Value: false 354 | Field of View: 0.7853981852531433 355 | Focal Point: 356 | X: 10.536402702331543 357 | Y: 71.63034057617188 358 | Z: 0.04836302623152733 359 | Focal Shape Fixed Size: false 360 | Focal Shape Size: 0.05000000074505806 361 | Invert Z Axis: false 362 | Name: park1_view 363 | Near Clip Distance: 0.009999999776482582 364 | Pitch: 1.5697963237762451 365 | Target Frame: 366 | Yaw: 3.2935829162597656 367 | Window Geometry: 368 | Displays: 369 | collapsed: false 370 | Height: 999 371 | Hide Left Dock: false 372 | Hide Right Dock: true 373 | QMainWindow State: 000000ff00000000fd00000004000000000000044300000391fc020000000efb0000001200530065006c0065006300740069006f006e010000003b000000940000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000d5000002f7000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065000000033e0000020c0000000000000000fb0000000a0049006d006100670065010000036e0000001e0000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c5000000c70000000000000000fb0000000a0049006d00610067006501000002c3000000c700000000000000000000000100000152000004f1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000047000004f1000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d00000039fc0100000002fb0000000800540069006d006500000000000000073d0000035c00fffffffb0000000800540069006d006501000000000000045000000000000000000000032b0000039100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 374 | Selection: 375 | collapsed: false 376 | Time: 377 | collapsed: false 378 | Tool Properties: 379 | collapsed: false 380 | Views: 381 | collapsed: true 382 | Width: 1908 383 | X: -32 384 | Y: -32 385 | -------------------------------------------------------------------------------- /src/utils.cpp: -------------------------------------------------------------------------------- 1 | #include "include/utils.h" 2 | void load_pose_with_time( 3 | const std::string &pose_file, 4 | std::vector> &pose_list, 5 | std::vector &time_list) { 6 | time_list.clear(); 7 | pose_list.clear(); 8 | std::ifstream fin(pose_file); 9 | std::string line; 10 | Eigen::Matrix temp_matrix; 11 | while (getline(fin, line)) { 12 | std::istringstream sin(line); 13 | std::vector Waypoints; 14 | std::string info; 15 | int number = 0; 16 | while (getline(sin, info, ',')) { 17 | if (number == 0) { 18 | double time; 19 | std::stringstream data; 20 | data << info; 21 | data >> time; 22 | time_list.push_back(time); 23 | number++; 24 | } else { 25 | double p; 26 | std::stringstream data; 27 | data << info; 28 | data >> p; 29 | temp_matrix[number - 1] = p; 30 | if (number == 7) { 31 | Eigen::Vector3d translation(temp_matrix[0], temp_matrix[1], 32 | temp_matrix[2]); 33 | Eigen::Quaterniond q(temp_matrix[3], temp_matrix[4], temp_matrix[5], 34 | temp_matrix[6]); 35 | std::pair single_pose; 36 | single_pose.first = translation; 37 | single_pose.second = q.toRotationMatrix(); 38 | pose_list.push_back(single_pose); 39 | } 40 | number++; 41 | } 42 | } 43 | } 44 | } 45 | 46 | void load_cu_pose_with_time( 47 | const std::string &pose_file, 48 | std::vector> &pose_list, 49 | std::vector &time_list) { 50 | time_list.clear(); 51 | pose_list.clear(); 52 | std::ifstream fin(pose_file); 53 | std::string line; 54 | Eigen::Matrix temp_matrix; 55 | while (getline(fin, line)) { 56 | std::istringstream sin(line); 57 | std::vector Waypoints; 58 | std::string info; 59 | int number = 0; 60 | while (getline(sin, info, ',')) { 61 | if (number == 0) { 62 | double time; 63 | std::stringstream data; 64 | data << info; 65 | data >> time; 66 | time_list.push_back(time); 67 | number++; 68 | } else { 69 | double p; 70 | std::stringstream data; 71 | data << info; 72 | data >> p; 73 | temp_matrix[number - 1] = p; 74 | if (number == 12) { 75 | Eigen::Vector3d translation(temp_matrix[3], temp_matrix[7], 76 | temp_matrix[11]); 77 | Eigen::Matrix3d rotation; 78 | rotation << temp_matrix[0], temp_matrix[1], temp_matrix[2], 79 | temp_matrix[4], temp_matrix[5], temp_matrix[6], temp_matrix[8], 80 | temp_matrix[9], temp_matrix[10]; 81 | std::pair single_pose; 82 | single_pose.first = translation; 83 | single_pose.second = rotation; 84 | pose_list.push_back(single_pose); 85 | } 86 | number++; 87 | } 88 | } 89 | } 90 | } 91 | 92 | void load_pose_with_frame( 93 | const std::string &pose_file, 94 | std::vector> &pose_list, 95 | std::vector &frame_number_list) { 96 | frame_number_list.clear(); 97 | pose_list.clear(); 98 | std::ifstream fin(pose_file); 99 | std::string line; 100 | Eigen::Matrix temp_matrix; 101 | while (getline(fin, line)) { 102 | std::istringstream sin(line); 103 | std::vector Waypoints; 104 | std::string info; 105 | int number = 0; 106 | while (getline(sin, info, ' ')) { 107 | if (number == 0) { 108 | int frame_number; 109 | std::stringstream data; 110 | data << info; 111 | data >> frame_number; 112 | frame_number_list.push_back(frame_number); 113 | number++; 114 | } else { 115 | double p; 116 | std::stringstream data; 117 | data << info; 118 | data >> p; 119 | temp_matrix[number - 1] = p; 120 | if (number == 12) { 121 | Eigen::Vector3d translation(temp_matrix[3], temp_matrix[7], 122 | temp_matrix[11]); 123 | Eigen::Matrix3d rotation; 124 | rotation << temp_matrix[0], temp_matrix[1], temp_matrix[2], 125 | temp_matrix[4], temp_matrix[5], temp_matrix[6], temp_matrix[8], 126 | temp_matrix[9], temp_matrix[10]; 127 | std::pair single_pose; 128 | single_pose.first = translation; 129 | single_pose.second = rotation; 130 | pose_list.push_back(single_pose); 131 | } 132 | number++; 133 | } 134 | } 135 | } 136 | } 137 | 138 | void load_evo_pose_with_time( 139 | const std::string &pose_file, 140 | std::vector> &pose_list, 141 | std::vector &time_list) { 142 | time_list.clear(); 143 | pose_list.clear(); 144 | std::ifstream fin(pose_file); 145 | std::string line; 146 | Eigen::Matrix temp_matrix; 147 | while (getline(fin, line)) { 148 | std::istringstream sin(line); 149 | std::vector Waypoints; 150 | std::string info; 151 | int number = 0; 152 | while (getline(sin, info, ' ')) { 153 | if (number == 0) { 154 | double time; 155 | std::stringstream data; 156 | data << info; 157 | data >> time; 158 | time_list.push_back(time); 159 | number++; 160 | } else { 161 | double p; 162 | std::stringstream data; 163 | data << info; 164 | data >> p; 165 | temp_matrix[number - 1] = p; 166 | if (number == 7) { 167 | Eigen::Vector3d translation(temp_matrix[0], temp_matrix[1], 168 | temp_matrix[2]); 169 | Eigen::Quaterniond q(temp_matrix[6], temp_matrix[3], temp_matrix[4], 170 | temp_matrix[5]); 171 | std::pair single_pose; 172 | single_pose.first = translation; 173 | single_pose.second = q.toRotationMatrix(); 174 | pose_list.push_back(single_pose); 175 | } 176 | number++; 177 | } 178 | } 179 | } 180 | } 181 | 182 | int findPoseIndexUsingTime(std::vector &time_list, double &time) { 183 | double time_inc = 10000000000; 184 | int min_index = -1; 185 | for (size_t i = 0; i < time_list.size(); i++) { 186 | if (fabs(time_list[i] - time) < time_inc) { 187 | time_inc = fabs(time_list[i] - time); 188 | min_index = i; 189 | } 190 | } 191 | return min_index; 192 | } 193 | 194 | pcl::PointXYZI vec2point(const Eigen::Vector3d &vec) { 195 | pcl::PointXYZI pi; 196 | pi.x = vec[0]; 197 | pi.y = vec[1]; 198 | pi.z = vec[2]; 199 | return pi; 200 | } 201 | // Eigen::Vector3d point2vec(const pcl::PointXYZI &pi) { 202 | // return Eigen::Vector3d(pi.x, pi.y, pi.z); 203 | // } 204 | 205 | Eigen::Vector3d normal2vec(const pcl::PointXYZINormal &pi) { 206 | Eigen::Vector3d vec(pi.normal_x, pi.normal_y, pi.normal_z); 207 | return vec; 208 | } 209 | 210 | double time_inc(std::chrono::_V2::system_clock::time_point &t_end, 211 | std::chrono::_V2::system_clock::time_point &t_begin) { 212 | return std::chrono::duration_cast>(t_end - 213 | t_begin) 214 | .count() * 215 | 1000; 216 | } 217 | 218 | double calc_overlap(const pcl::PointCloud::Ptr &cloud1, 219 | const pcl::PointCloud::Ptr &cloud2, 220 | double dis_threshold) { 221 | int point_kip = 2; 222 | double match_num = 0; 223 | pcl::KdTreeFLANN::Ptr kd_tree( 224 | new pcl::KdTreeFLANN); 225 | kd_tree->setInputCloud(cloud2); 226 | std::vector pointIdxNKNSearch(1); 227 | std::vector pointNKNSquaredDistance(1); 228 | for (size_t i = 0; i < cloud1->size(); i += point_kip) { 229 | pcl::PointXYZI searchPoint = cloud1->points[i]; 230 | if (kd_tree->nearestKSearch(searchPoint, 1, pointIdxNKNSearch, 231 | pointNKNSquaredDistance) > 0) { 232 | if (pointNKNSquaredDistance[0] < dis_threshold * dis_threshold) { 233 | match_num++; 234 | } 235 | } 236 | } 237 | // std::cout << "cloud1 size:" << cloud1->size() 238 | // << " cloud2 size: " << cloud2->size() << " match size:" << 239 | // match_num 240 | // << std::endl; 241 | double overlap = 242 | 2 * match_num * point_kip / (cloud1->size() + cloud2->size()); 243 | return overlap; 244 | } 245 | 246 | double calc_overlap(const pcl::PointCloud::Ptr &cloud1, 247 | const pcl::PointCloud::Ptr &cloud2, 248 | double dis_threshold, int skip_num) { 249 | double match_num = 0; 250 | pcl::KdTreeFLANN::Ptr kd_tree( 251 | new pcl::KdTreeFLANN); 252 | kd_tree->setInputCloud(cloud2); 253 | std::vector pointIdxNKNSearch(1); 254 | std::vector pointNKNSquaredDistance(1); 255 | for (size_t i = 0; i < cloud1->size(); i += skip_num) { 256 | pcl::PointXYZI searchPoint = cloud1->points[i]; 257 | if (kd_tree->nearestKSearch(searchPoint, 1, pointIdxNKNSearch, 258 | pointNKNSquaredDistance) > 0) { 259 | if (pointNKNSquaredDistance[0] < dis_threshold * dis_threshold) { 260 | match_num++; 261 | } 262 | } 263 | } 264 | // std::cout << "cloud1 size:" << cloud1->size() 265 | // << " cloud2 size: " << cloud2->size() << " match size:" << 266 | // match_num 267 | // << std::endl; 268 | double overlap = 269 | (2 * match_num * skip_num) / (cloud1->size() + cloud2->size()); 270 | return overlap; 271 | } 272 | -------------------------------------------------------------------------------- /supply/Supplementary_Material_for_BTC.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/hku-mars/btc_descriptor/742af157036144edad9a8350330c0158ea1a40d5/supply/Supplementary_Material_for_BTC.pdf --------------------------------------------------------------------------------