├── .gitignore
├── LICENSE
├── README.md
├── assets
├── cloud_bin_21.pth
├── cloud_bin_34.pth
├── demo.png
├── dist_thresh.txt
├── fix_knn_feats.png
├── inlier_thresh.txt
├── results.png
└── teaser_predator.jpg
├── common
├── colors.py
├── math
│ ├── random.py
│ ├── se3.py
│ └── so3.py
├── math_torch
│ └── se3.py
├── misc.py
└── torch.py
├── configs
├── benchmarks
│ ├── 3DLoMatch
│ │ ├── 7-scenes-redkitchen
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-home_at-home_at_scan1_2013_jan_1
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-home_md-home_md_scan9_2012_sep_30
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_uc-scan3
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_umd-maryland_hotel1
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_umd-maryland_hotel3
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ ├── sun3d-mit_76_studyroom-76-1studyroom2
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ │ └── sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika
│ │ │ ├── gt.info
│ │ │ ├── gt.log
│ │ │ └── gt_overlap.log
│ └── 3DMatch
│ │ ├── 7-scenes-redkitchen
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-home_at-home_at_scan1_2013_jan_1
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-home_md-home_md_scan9_2012_sep_30
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_uc-scan3
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_umd-maryland_hotel1
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-hotel_umd-maryland_hotel3
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ ├── sun3d-mit_76_studyroom-76-1studyroom2
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
│ │ └── sun3d-mit_lab_hj-lab_hj_tea_nov_2_2012_scan1_erika
│ │ ├── gt.info
│ │ ├── gt.log
│ │ └── gt_overlap.log
├── indoor
│ ├── 3DLoMatch.pkl
│ ├── 3DMatch.pkl
│ ├── train_3dmatch.txt
│ ├── train_info.pkl
│ ├── val_3dmatch.txt
│ └── val_info.pkl
├── kitti
│ ├── test_kitti.txt
│ ├── train_kitti.txt
│ └── val_kitti.txt
├── modelnet
│ ├── modelnet40_all.txt
│ ├── modelnet40_half1.txt
│ └── modelnet40_half2.txt
├── models.py
├── test
│ ├── indoor.yaml
│ ├── kitti.yaml
│ └── modelnet.yaml
└── train
│ ├── indoor.yaml
│ ├── kitti.yaml
│ └── modelnet.yaml
├── cpp_wrappers
├── compile_wrappers.sh
├── cpp_neighbors
│ ├── build.bat
│ ├── neighbors
│ │ ├── neighbors.cpp
│ │ └── neighbors.h
│ ├── setup.py
│ └── wrapper.cpp
├── cpp_subsampling
│ ├── build.bat
│ ├── grid_subsampling
│ │ ├── grid_subsampling.cpp
│ │ └── grid_subsampling.h
│ ├── setup.py
│ └── wrapper.cpp
└── cpp_utils
│ ├── cloud
│ ├── cloud.cpp
│ └── cloud.h
│ └── nanoflann
│ └── nanoflann.hpp
├── datasets
├── __init__.py
├── dataloader.py
├── indoor.py
├── kitti.py
├── modelnet.py
└── transforms.py
├── kernels
├── dispositions
│ └── k_015_center_3D.ply
└── kernel_points.py
├── lib
├── __init__.py
├── benchmark.py
├── benchmark_utils.py
├── loss.py
├── ply.py
├── tester.py
├── timer.py
├── trainer.py
└── utils.py
├── main.py
├── models
├── __init__.py
├── architectures.py
├── blocks.py
└── gcn.py
├── requirements.txt
└── scripts
├── cal_overlap.py
├── demo.py
├── download_data_weight.sh
└── evaluate_predator.py
/.gitignore:
--------------------------------------------------------------------------------
1 | snapshot/
2 | scripts.py
3 | *.so
4 | *.zip
5 | data/
6 | weights/
7 | __pycache__/
8 | build/
9 | dump/
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2021 Shengyu Huang, Zan Gojcic
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | ## PREDATOR: Registration of 3D Point Clouds with Low Overlap (CVPR 2021, Oral)
2 | This repository represents the official implementation of the paper:
3 |
4 | ### [PREDATOR: Registration of 3D Point Clouds with Low Overlap](https://arxiv.org/abs/2011.13005)
5 |
6 | \*[Shengyu Huang](https://shengyuh.github.io), \*[Zan Gojcic](https://zgojcic.github.io/), [Mikhail Usvyatsov](https://aelphy.github.io), [Andreas Wieser](https://gseg.igp.ethz.ch/people/group-head/prof-dr--andreas-wieser.html), [Konrad Schindler](https://prs.igp.ethz.ch/group/people/person-detail.schindler.html)\
7 | |[ETH Zurich](https://igp.ethz.ch/) | \* Equal contribution
8 |
9 | For implementation using MinkowskiEngine backbone, please check [this](https://github.com/ShengyuH/OverlapPredator.Mink)
10 |
11 | For more information, please see the [project website](https://overlappredator.github.io)
12 |
13 | 
14 |
15 |
16 |
17 | ### Contact
18 | If you have any questions, please let us know:
19 | - Shengyu Huang {shengyu.huang@geod.baug.ethz.ch}
20 | - Zan Gojcic {zan.gojcic@geod.baug.ethz.ch}
21 |
22 | ## News
23 | - 2021-08-09: We've updated arxiv version of our [paper](https://arxiv.org/abs/2011.13005) with improved performance!
24 | - 2021-06-02: Fix feature gathering bug in k-nn graph, please see improved performance in this [issue](https://github.com/overlappredator/OverlapPredator/issues/15). Stay tunned for updates on other experiments!
25 | - 2021-05-31: Check our video and poster on [project page](https://overlappredator.github.io)!
26 | - 2021-03-25: Camera ready is on arXiv! I also gave a talk on Predator(中文), you can find the recording here: [Bilibili](https://www.bilibili.com/video/BV1UK4y1U7Gs), [Youtube](https://www.youtube.com/watch?v=AZQGJa6R_4I&t=1563s)
27 | - 2021-02-28: MinkowskiEngine-based PREDATOR [release](https://github.com/ShengyuH/OverlapPredator.Mink.git)
28 | - 2020-11-30: Code and paper release
29 |
30 |
31 | ## Instructions
32 | This code has been tested on
33 | - Python 3.8.5, PyTorch 1.7.1, CUDA 11.2, gcc 9.3.0, GeForce RTX 3090/GeForce GTX 1080Ti
34 |
35 | **Note**: We observe random data loader crashes due to memory issues, if you observe similar issues, please consider reducing the number of workers or increasing CPU RAM. We now released a sparse convolution-based Predator, have a look [here](https://github.com/ShengyuH/OverlapPredator.Mink.git)!
36 |
37 | ### Requirements
38 | To create a virtual environment and install the required dependences please run:
39 | ```shell
40 | git clone https://github.com/overlappredator/OverlapPredator.git
41 | virtualenv predator; source predator/bin/activate
42 | cd OverlapPredator; pip install -r requirements.txt
43 | cd cpp_wrappers; sh compile_wrappers.sh; cd ..
44 | ```
45 | in your working folder.
46 |
47 | ### Datasets and pretrained models
48 | For KITTI dataset, please follow the instruction on [KITTI Odometry website](http://www.cvlibs.net/datasets/kitti/eval_odometry.php) to download the KITTI odometry training set.
49 |
50 | We provide
51 | - preprocessed 3DMatch pairwise datasets (voxel-grid subsampled fragments together with their ground truth transformation matrices)
52 | - raw dense 3DMatch datasets
53 | - modelnet dataset
54 | - pretrained models on 3DMatch, KITTI and Modelnet
55 |
56 | The preprocessed data and models can be downloaded by running:
57 | ```shell
58 | sh scripts/download_data_weight.sh
59 | ```
60 |
61 | To download raw dense 3DMatch data, please run:
62 | ```shell
63 | wget --no-check-certificate --show-progress https://share.phys.ethz.ch/~gsg/pairwise_reg/3dmatch.zip
64 | unzip 3dmatch.zip
65 | ```
66 |
67 | The folder is organised as follows:
68 |
69 | - `3dmatch`
70 | - `train`
71 | - `7-scenes-chess`
72 | - `fragments`
73 | - `cloud_bin_*.ply`
74 | - ...
75 | - `poses`
76 | - `cloud_bin_*.txt`
77 | - ...
78 | - ...
79 | - `test`
80 |
81 | ### 3DMatch(Indoor)
82 | #### Train
83 | After creating the virtual environment and downloading the datasets, Predator can be trained using:
84 | ```shell
85 | python main.py configs/train/indoor.yaml
86 | ```
87 |
88 | #### Evaluate
89 | For 3DMatch, to reproduce Table 2 in our main paper, we first extract features and overlap/matachability scores by running:
90 | ```shell
91 | python main.py configs/test/indoor.yaml
92 | ```
93 | the features together with scores will be saved to ```snapshot/indoor/3DMatch```. The estimation of the transformation parameters using RANSAC can then be carried out using:
94 | ```shell
95 | for N_POINTS in 250 500 1000 2500 5000
96 | do
97 | python scripts/evaluate_predator.py --source_path snapshot/indoor/3DMatch --n_points $N_POINTS --benchmark 3DMatch --exp_dir snapshot/indoor/est_traj --sampling prob
98 | done
99 | ```
100 | dependent on ```n_points``` used by RANSAC, this might take a few minutes. The final results are stored in ```snapshot/indoor/est_traj/{benchmark}_{n_points}_prob/result```. To evaluate PREDATOR on 3DLoMatch benchmark, please also change ```3DMatch``` to ```3DLoMatch``` in ```configs/test/indoor.yaml```.
101 |
102 | #### Demo
103 | We prepared a small demo, which demonstrates the whole Predator pipeline using two random fragments from the 3DMatch dataset. To carry out the demo, please run:
104 | ```shell
105 | python scripts/demo.py configs/test/indoor.yaml
106 | ```
107 |
108 | The demo script will visualize input point clouds, inferred overlap regions, and point cloud aligned with the estimated transformation parameters:
109 |
110 |
111 |
112 | ### ModelNet(Synthetic)
113 | #### Train
114 | To train PREDATOR on ModelNet, please run:
115 | ```
116 | python main.py configs/train/modelnet.yaml
117 | ```
118 |
119 | We provide a small script to evaluate Predator on ModelNet test set, please run:
120 | ```
121 | python main.py configs/test/modelnet.yaml
122 | ```
123 | The rotation and translation errors could be better/worse than the reported ones due to randomness in RANSAC.
124 |
125 | ### KITTI(Outdoor)
126 | We provide a small script to evaluate Predator on KITTI test set, after configuring KITTI dataset, please run:
127 | ```
128 | python main.py configs/test/kitti.yaml
129 | ```
130 | the results will be saved to the log file.
131 |
132 |
133 | ### Custom dataset
134 | We have a few tips for train/test on custom dataset
135 |
136 | - If it's similar indoor scenes, please run ```demo.py``` first to check the generalisation ability before retraining
137 | - Remember to voxel-downsample the data in your data loader, see ```kitti.py``` for reference
138 |
139 | ### Citation
140 | If you find this code useful for your work or use it in your project, please consider citing:
141 |
142 | ```shell
143 | @InProceedings{Huang_2021_CVPR,
144 | author = {Huang, Shengyu and Gojcic, Zan and Usvyatsov, Mikhail and Wieser, Andreas and Schindler, Konrad},
145 | title = {Predator: Registration of 3D Point Clouds With Low Overlap},
146 | booktitle = {Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR)},
147 | month = {June},
148 | year = {2021},
149 | pages = {4267-4276}
150 | }
151 | ```
152 |
153 | ### Acknowledgments
154 | In this project we use (parts of) the official implementations of the followin works:
155 |
156 | - [FCGF](https://github.com/chrischoy/FCGF) (KITTI preprocessing)
157 | - [D3Feat](https://github.com/XuyangBai/D3Feat.pytorch) (KPConv backbone)
158 | - [3DSmoothNet](https://github.com/zgojcic/3DSmoothNet) (3DMatch preparation)
159 | - [MultiviewReg](https://github.com/zgojcic/3D_multiview_reg) (3DMatch benchmark)
160 | - [SuperGlue](https://github.com/magicleap/SuperGluePretrainedNetwork) (Transformer part)
161 | - [DGCNN](https://github.com/WangYueFt/dgcnn) (self-gnn)
162 | - [RPMNet](https://github.com/yewzijian/RPMNet) (ModelNet preprocessing and evaluation)
163 |
164 | We thank the respective authors for open sourcing their methods. We would also like to thank reviewers, especially reviewer 2 for his/her valuable inputs.
165 |
--------------------------------------------------------------------------------
/assets/cloud_bin_21.pth:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/cloud_bin_21.pth
--------------------------------------------------------------------------------
/assets/cloud_bin_34.pth:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/cloud_bin_34.pth
--------------------------------------------------------------------------------
/assets/demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/demo.png
--------------------------------------------------------------------------------
/assets/dist_thresh.txt:
--------------------------------------------------------------------------------
1 | method 0.01 0.02 0.03 0.04 0.05 0.06 0.07 0.08 0.09 0.1 0.11 0.12 0.13 0.14 0.15 0.16 0.17 0.18 0.19 0.2
2 | 3DMatch 0.34988788 1.735477 6.3130245 13.2243185 20.68582 28.49041 34.01513 40.062992 45.687683 52.00012 55.463696 59.081406 61.986275 65.45967 68.43626 70.95725 73.55156 76.07139 77.85846 80.27285
3 | FPFH 0.32518435 3.0640497 7.408897 12.879427 17.654156 21.894594 24.814766 28.676664 32.31617 35.307827 38.895893 41.363243 44.120644 47.001804 49.11531 52.33542 55.02593 56.853123 59.70479 61.781036
4 | SpinImages 0.2650882 1.4736623 3.4342945 5.703008 8.022694 9.878324 12.34205 15.342176 18.735947 21.89705 24.729364 28.054333 31.125975 33.943203 36.965153 40.642887 43.33119 46.57485 49.260128 52.152588
5 | SHOT 0.47008017 2.6745644 5.1028447 7.4799767 9.238545 11.927085 16.089037 18.879076 22.094217 24.974531 27.351418 29.76674 32.573856 34.916573 37.086315 40.306644 43.138355 45.73636 48.786892 50.972153
6 | Predator 1.598646 43.764183 72.060312 84.277961 90.004648 92.64463 94.014723 94.990602 95.96624 96.601441 96.806433 97.099785 97.35597 97.35597 97.380674 97.380674 97.611186 97.90688 98.178721 98.238818
7 | FCGF 4.135307 50.302743 76.513382 87.786066 92.033676 93.6785 94.900559 96.311261 96.912816 97.353521 97.738293 98.016699 98.573519 98.633615 98.676423 98.731733 98.854555 98.854555 98.854555 98.99945
8 | 3DSN 6.925493 42.819659 65.908609 78.549499 85.100889 88.986995 91.870439 93.402519 94.398583 95.019629 95.537113 95.72003 95.900319 96.135917 96.358351 96.631008 96.831329 96.911342 97.031535 97.249845
9 | D3Feat 1.326839 31.021349 61.608349 75.575873 82.991841 88.585381 91.007284 92.794678 94.556689 95.631483 96.580489 96.768193 96.8176 96.920505 97.085318 97.128126 97.695815 97.816008 97.985607 97.985607
10 |
--------------------------------------------------------------------------------
/assets/fix_knn_feats.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/fix_knn_feats.png
--------------------------------------------------------------------------------
/assets/inlier_thresh.txt:
--------------------------------------------------------------------------------
1 | method 0.01 0.02 0.03 0.04 0.05 0.06 0.07 0.08 0.09 0.10 0.11 0.12 0.13 0.14 0.15 0.16 0.17 0.18 0.19 0.2
2 | 3DMatch 93.57423 84.989296 72.26616 60.18662 50.84514 40.988052 35.264496 29.492676 24.875406 20.927317 18.053923 14.7144 12.210866 10.735968 9.550746 8.107913 7.4702764 6.172435 5.2574573 4.3098807
3 | FPFH 84.33316 68.71096 54.144688 43.4266 35.885315 29.24774 24.669365 21.693983 18.398415 15.19658 13.052581 10.593815 9.197111 7.121167 6.0142927 5.459413 4.7025414 3.7748396 3.2582376 2.9224794
4 | SpinImages 80.370415 57.09011 41.317715 30.377916 22.666761 16.668486 12.008004 9.49888 6.9450083 5.2102103 4.6000204 3.9652426 3.6801224 2.8298047 2.4588833 1.6771933 1.4722013 1.3379945 1.1484778 0.9681894
5 | SHOT 74.7338 55.754692 41.421146 31.38755 23.82493 18.377901 14.077372 11.229745 9.498036 7.2400875 6.259093 5.4715004 4.264607 3.6964087 3.070859 2.418819 2.0778346 1.5370839 1.5123804 1.4522841
6 | Predator 98.859889 97.909077 97.500866 97.125458 96.601441 95.734758 94.609147 94.146195 93.172484 92.713764 92.183001 91.71345 91.044471 90.592342 90.185631 89.322503 88.736845 88.36471 87.145778 86.287232
7 | FCGF 99.526474 98.940171 98.226632 97.884006 97.353521 96.627542 96.318829 96.029037 95.339938 94.679256 93.99646 93.517994 92.618115 92.43327 92.128233 91.267739 90.514984 90.144248 89.87309 89.340131
8 | 3DSN 99.053496 97.806905 97.138431 96.063319 95.019629 93.43627 92.676226 91.676057 89.926433 88.093154 86.428362 84.396438 83.500374 82.442937 80.94519 78.946443 77.480061 75.891795 74.209464 72.884469
9 | D3Feat 98.452534 97.660423 97.020136 96.768193 95.631483 94.327522 92.314021 90.721366 89.756974 88.743718 88.126642 87.331697 85.993739 84.35534 83.309026 82.154434 80.440724 79.07386 77.657352 75.881642
10 |
--------------------------------------------------------------------------------
/assets/results.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/results.png
--------------------------------------------------------------------------------
/assets/teaser_predator.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/assets/teaser_predator.jpg
--------------------------------------------------------------------------------
/common/colors.py:
--------------------------------------------------------------------------------
1 | """Useful color codes"""
2 | ORANGE = [239, 124, 0]
3 | BLUE = [0, 61, 124]
--------------------------------------------------------------------------------
/common/math/random.py:
--------------------------------------------------------------------------------
1 | """Functions for random sampling"""
2 | import numpy as np
3 |
4 |
5 | def uniform_2_sphere(num: int = None):
6 | """Uniform sampling on a 2-sphere
7 |
8 | Source: https://gist.github.com/andrewbolster/10274979
9 |
10 | Args:
11 | num: Number of vectors to sample (or None if single)
12 |
13 | Returns:
14 | Random Vector (np.ndarray) of size (num, 3) with norm 1.
15 | If num is None returned value will have size (3,)
16 |
17 | """
18 | if num is not None:
19 | phi = np.random.uniform(0.0, 2 * np.pi, num)
20 | cos_theta = np.random.uniform(-1.0, 1.0, num)
21 | else:
22 | phi = np.random.uniform(0.0, 2 * np.pi)
23 | cos_theta = np.random.uniform(-1.0, 1.0)
24 |
25 | theta = np.arccos(cos_theta)
26 | x = np.sin(theta) * np.cos(phi)
27 | y = np.sin(theta) * np.sin(phi)
28 | z = np.cos(theta)
29 |
30 | return np.stack((x, y, z), axis=-1)
31 |
32 |
33 | if __name__ == '__main__':
34 | # Visualize sampling
35 | from vtk_visualizer.plot3d import plotxyz
36 | rand_2s = uniform_2_sphere(10000)
37 | plotxyz(rand_2s, block=True)
38 |
--------------------------------------------------------------------------------
/common/math/se3.py:
--------------------------------------------------------------------------------
1 | import numpy as np
2 | from scipy.spatial.transform import Rotation
3 |
4 |
5 | def identity():
6 | return np.eye(3, 4)
7 |
8 |
9 | def transform(g: np.ndarray, pts: np.ndarray):
10 | """ Applies the SE3 transform
11 |
12 | Args:
13 | g: SE3 transformation matrix of size ([B,] 3/4, 4)
14 | pts: Points to be transformed ([B,] N, 3)
15 |
16 | Returns:
17 | transformed points of size (N, 3)
18 | """
19 | rot = g[..., :3, :3] # (3, 3)
20 | trans = g[..., :3, 3] # (3)
21 |
22 | transformed = pts[..., :3] @ np.swapaxes(rot, -1, -2) + trans[..., None, :]
23 | return transformed
24 |
25 |
26 | def inverse(g: np.ndarray):
27 | """Returns the inverse of the SE3 transform
28 |
29 | Args:
30 | g: ([B,] 3/4, 4) transform
31 |
32 | Returns:
33 | ([B,] 3/4, 4) matrix containing the inverse
34 |
35 | """
36 | rot = g[..., :3, :3] # (3, 3)
37 | trans = g[..., :3, 3] # (3)
38 |
39 | inv_rot = np.swapaxes(rot, -1, -2)
40 | inverse_transform = np.concatenate([inv_rot, inv_rot @ -trans[..., None]], axis=-1)
41 | if g.shape[-2] == 4:
42 | inverse_transform = np.concatenate([inverse_transform, [[0.0, 0.0, 0.0, 1.0]]], axis=-2)
43 |
44 | return inverse_transform
45 |
46 |
47 | def concatenate(a: np.ndarray, b: np.ndarray):
48 | """ Concatenate two SE3 transforms
49 |
50 | Args:
51 | a: First transform ([B,] 3/4, 4)
52 | b: Second transform ([B,] 3/4, 4)
53 |
54 | Returns:
55 | a*b ([B, ] 3/4, 4)
56 |
57 | """
58 |
59 | r_a, t_a = a[..., :3, :3], a[..., :3, 3]
60 | r_b, t_b = b[..., :3, :3], b[..., :3, 3]
61 |
62 | r_ab = r_a @ r_b
63 | t_ab = r_a @ t_b[..., None] + t_a[..., None]
64 |
65 | concatenated = np.concatenate([r_ab, t_ab], axis=-1)
66 |
67 | if a.shape[-2] == 4:
68 | concatenated = np.concatenate([concatenated, [[0.0, 0.0, 0.0, 1.0]]], axis=-2)
69 |
70 | return concatenated
71 |
72 |
73 | def from_xyzquat(xyzquat):
74 | """Constructs SE3 matrix from x, y, z, qx, qy, qz, qw
75 |
76 | Args:
77 | xyzquat: np.array (7,) containing translation and quaterion
78 |
79 | Returns:
80 | SE3 matrix (4, 4)
81 | """
82 | rot = Rotation.from_quat(xyzquat[3:])
83 | trans = rot.apply(-xyzquat[:3])
84 | transform = np.concatenate([rot.as_dcm(), trans[:, None]], axis=1)
85 | transform = np.concatenate([transform, [[0.0, 0.0, 0.0, 1.0]]], axis=0)
86 |
87 | return transform
--------------------------------------------------------------------------------
/common/math/so3.py:
--------------------------------------------------------------------------------
1 | """
2 | Rotation related functions for numpy arrays
3 | """
4 |
5 | import numpy as np
6 | from scipy.spatial.transform import Rotation
7 |
8 |
9 | def dcm2euler(mats: np.ndarray, seq: str = 'zyx', degrees: bool = True):
10 | """Converts rotation matrix to euler angles
11 |
12 | Args:
13 | mats: (B, 3, 3) containing the B rotation matricecs
14 | seq: Sequence of euler rotations (default: 'zyx')
15 | degrees (bool): If true (default), will return in degrees instead of radians
16 |
17 | Returns:
18 |
19 | """
20 |
21 | eulers = []
22 | for i in range(mats.shape[0]):
23 | r = Rotation.from_dcm(mats[i])
24 | eulers.append(r.as_euler(seq, degrees=degrees))
25 | return np.stack(eulers)
26 |
27 |
28 | def transform(g: np.ndarray, pts: np.ndarray):
29 | """ Applies the SO3 transform
30 |
31 | Args:
32 | g: SO3 transformation matrix of size (3, 3)
33 | pts: Points to be transformed (N, 3)
34 |
35 | Returns:
36 | transformed points of size (N, 3)
37 |
38 | """
39 | rot = g[:3, :3] # (3, 3)
40 | transformed = pts @ rot.transpose()
41 | return transformed
42 |
--------------------------------------------------------------------------------
/common/math_torch/se3.py:
--------------------------------------------------------------------------------
1 | """ 3-d rigid body transformation group
2 | """
3 | import torch
4 |
5 |
6 | def identity(batch_size):
7 | return torch.eye(3, 4)[None, ...].repeat(batch_size, 1, 1)
8 |
9 |
10 | def inverse(g):
11 | """ Returns the inverse of the SE3 transform
12 |
13 | Args:
14 | g: (B, 3/4, 4) transform
15 |
16 | Returns:
17 | (B, 3, 4) matrix containing the inverse
18 |
19 | """
20 | # Compute inverse
21 | rot = g[..., 0:3, 0:3]
22 | trans = g[..., 0:3, 3]
23 | inverse_transform = torch.cat([rot.transpose(-1, -2), rot.transpose(-1, -2) @ -trans[..., None]], dim=-1)
24 |
25 | return inverse_transform
26 |
27 |
28 | def concatenate(a, b):
29 | """Concatenate two SE3 transforms,
30 | i.e. return a@b (but note that our SE3 is represented as a 3x4 matrix)
31 |
32 | Args:
33 | a: (B, 3/4, 4)
34 | b: (B, 3/4, 4)
35 |
36 | Returns:
37 | (B, 3/4, 4)
38 | """
39 |
40 | rot1 = a[..., :3, :3]
41 | trans1 = a[..., :3, 3]
42 | rot2 = b[..., :3, :3]
43 | trans2 = b[..., :3, 3]
44 |
45 | rot_cat = rot1 @ rot2
46 | trans_cat = rot1 @ trans2[..., None] + trans1[..., None]
47 | concatenated = torch.cat([rot_cat, trans_cat], dim=-1)
48 |
49 | return concatenated
50 |
51 |
52 | def transform(g, a, normals=None):
53 | """ Applies the SE3 transform
54 |
55 | Args:
56 | g: SE3 transformation matrix of size ([1,] 3/4, 4) or (B, 3/4, 4)
57 | a: Points to be transformed (N, 3) or (B, N, 3)
58 | normals: (Optional). If provided, normals will be transformed
59 |
60 | Returns:
61 | transformed points of size (N, 3) or (B, N, 3)
62 |
63 | """
64 | R = g[..., :3, :3] # (B, 3, 3)
65 | p = g[..., :3, 3] # (B, 3)
66 |
67 | if len(g.size()) == len(a.size()):
68 | b = torch.matmul(a, R.transpose(-1, -2)) + p[..., None, :]
69 | else:
70 | raise NotImplementedError
71 | b = R.matmul(a.unsqueeze(-1)).squeeze(-1) + p # No batch. Not checked
72 |
73 | if normals is not None:
74 | rotated_normals = normals @ R.transpose(-1, -2)
75 | return b, rotated_normals
76 |
77 | else:
78 | return b
79 |
--------------------------------------------------------------------------------
/common/misc.py:
--------------------------------------------------------------------------------
1 | """
2 | Misc utilities
3 | """
4 |
5 | import argparse
6 | from datetime import datetime
7 | import logging
8 | import os
9 | import shutil
10 | import subprocess
11 | import sys
12 |
13 | import coloredlogs
14 | import git
15 |
16 |
17 | _logger = logging.getLogger()
18 |
19 |
20 | def print_info(opt, log_dir=None):
21 | """ Logs source code configuration
22 | """
23 | _logger.info('Command: {}'.format(' '.join(sys.argv)))
24 |
25 | # Print commit ID
26 | try:
27 | repo = git.Repo(search_parent_directories=True)
28 | git_sha = repo.head.object.hexsha
29 | git_date = datetime.fromtimestamp(repo.head.object.committed_date).strftime('%Y-%m-%d')
30 | git_message = repo.head.object.message
31 | _logger.info('Source is from Commit {} ({}): {}'.format(git_sha[:8], git_date, git_message.strip()))
32 |
33 | # Also create diff file in the log directory
34 | if log_dir is not None:
35 | with open(os.path.join(log_dir, 'compareHead.diff'), 'w') as fid:
36 | subprocess.run(['git', 'diff'], stdout=fid)
37 |
38 | except git.exc.InvalidGitRepositoryError:
39 | pass
40 |
41 | # Arguments
42 | arg_str = ['{}: {}'.format(key, value) for key, value in vars(opt).items()]
43 | arg_str = ', '.join(arg_str)
44 | #_logger.info('Arguments: {}'.format(arg_str))
45 |
46 |
47 | def prepare_logger(opt: argparse.Namespace, log_path: str = None):
48 | """Creates logging directory, and installs colorlogs
49 |
50 | Args:
51 | opt: Program arguments, should include --dev and --logdir flag.
52 | See get_parent_parser()
53 | log_path: Logging path (optional). This serves to overwrite the settings in
54 | argparse namespace
55 |
56 | Returns:
57 | logger (logging.Logger)
58 | log_path (str): Logging directory
59 | """
60 |
61 | if log_path is None:
62 | if opt.dev:
63 | log_path = '../logdev'
64 | shutil.rmtree(log_path, ignore_errors=True)
65 | else:
66 | datetime_str = datetime.now().strftime('%y%m%d_%H%M%S')
67 | if opt.name is not None:
68 | log_path = os.path.join(opt.logdir, datetime_str + '_' + opt.name)
69 | else:
70 | log_path = os.path.join(opt.logdir, datetime_str)
71 |
72 | os.makedirs(log_path, exist_ok=True)
73 | logger = logging.getLogger()
74 | coloredlogs.install(level='INFO', logger=logger)
75 | file_handler = logging.FileHandler('{}/log.txt'.format(log_path))
76 | log_formatter = logging.Formatter('%(asctime)s [%(levelname)s] %(name)s - %(message)s')
77 | file_handler.setFormatter(log_formatter)
78 | logger.addHandler(file_handler)
79 | print_info(opt, log_path)
80 | logger.info('Output and logs will be saved to {}'.format(log_path))
81 |
82 | return logger, log_path
83 |
--------------------------------------------------------------------------------
/common/torch.py:
--------------------------------------------------------------------------------
1 | """PyTorch related utility functions
2 | """
3 |
4 | import logging
5 | import os
6 | import pdb
7 | import shutil
8 | import sys
9 | import time
10 | import traceback
11 |
12 | import numpy as np
13 | import torch
14 | from torch.optim.optimizer import Optimizer
15 |
16 |
17 | def dict_all_to_device(tensor_dict, device):
18 | """Sends everything into a certain device """
19 | for k in tensor_dict:
20 | if isinstance(tensor_dict[k], torch.Tensor):
21 | tensor_dict[k] = tensor_dict[k].to(device)
22 |
23 |
24 | def to_numpy(tensor):
25 | """Wrapper around .detach().cpu().numpy() """
26 | if isinstance(tensor, torch.Tensor):
27 | return tensor.detach().cpu().numpy()
28 | elif isinstance(tensor, np.ndarray):
29 | return tensor
30 | else:
31 | raise NotImplementedError
32 |
33 |
34 | class CheckPointManager(object):
35 | """Manager for saving/managing pytorch checkpoints.
36 |
37 | Provides functionality similar to tf.Saver such as
38 | max_to_keep and keep_checkpoint_every_n_hours
39 | """
40 | def __init__(self, save_path: str = None, max_to_keep=5, keep_checkpoint_every_n_hours=10000.0):
41 |
42 | if max_to_keep <= 0:
43 | raise ValueError('max_to_keep must be at least 1')
44 |
45 | self._max_to_keep = max_to_keep
46 | self._keep_checkpoint_every_n_hours = keep_checkpoint_every_n_hours
47 |
48 | self._ckpt_dir = os.path.dirname(save_path)
49 | self._save_path = save_path + '-{}.pth' if save_path is not None else None
50 | self._logger = logging.getLogger(self.__class__.__name__)
51 | self._checkpoints_fname = os.path.join(self._ckpt_dir, 'checkpoints.txt')
52 |
53 | self._checkpoints_permanent = [] # Will not be deleted
54 | self._checkpoints_buffer = [] # Those which might still be deleted
55 | self._next_save_time = time.time()
56 | self._best_score = -float('inf')
57 | self._best_step = None
58 |
59 | os.makedirs(self._ckpt_dir, exist_ok=True)
60 | self._update_checkpoints_file()
61 |
62 | def _save_checkpoint(self, step, model, optimizer, score):
63 | save_name = self._save_path.format(step)
64 | state = {'state_dict': model.state_dict(),
65 | 'optimizer': optimizer.state_dict(),
66 | 'step': step}
67 | torch.save(state, save_name)
68 | self._logger.info('Saved checkpoint: {}'.format(save_name))
69 |
70 | self._checkpoints_buffer.append((save_name, time.time()))
71 |
72 | if score > self._best_score:
73 | best_save_name = self._save_path.format('best')
74 | shutil.copyfile(save_name, best_save_name)
75 | self._best_score = score
76 | self._best_step = step
77 | self._logger.info('Checkpoint is current best, score={:.3g}'.format(self._best_score))
78 |
79 | def _remove_old_checkpoints(self):
80 | while len(self._checkpoints_buffer) > self._max_to_keep:
81 | to_remove = self._checkpoints_buffer.pop(0)
82 |
83 | if to_remove[1] > self._next_save_time:
84 | self._checkpoints_permanent.append(to_remove)
85 | self._next_save_time = to_remove[1] + self._keep_checkpoint_every_n_hours * 3600
86 | else:
87 | os.remove(to_remove[0])
88 |
89 | def _update_checkpoints_file(self):
90 | checkpoints = [os.path.basename(c[0]) for c in self._checkpoints_permanent + self._checkpoints_buffer]
91 | with open(self._checkpoints_fname, 'w') as fid:
92 | fid.write('\n'.join(checkpoints))
93 | fid.write('\nBest step: {}'.format(self._best_step))
94 |
95 | def save(self, model: torch.nn.Module, optimizer: Optimizer, step: int, score: float = 0.0):
96 | """Save model checkpoint to file
97 |
98 | Args:
99 | model: Torch model
100 | optimizer: Torch optimizer
101 | step (int): Step, model will be saved as model-[step].pth
102 | score (float, optional): To determine which model is the best
103 | """
104 | if self._save_path is None:
105 | raise AssertionError('Checkpoint manager must be initialized with save path for save().')
106 |
107 | self._save_checkpoint(step, model, optimizer, score)
108 | self._remove_old_checkpoints()
109 | self._update_checkpoints_file()
110 |
111 | def load(self, save_path, model: torch.nn.Module = None, optimizer: Optimizer = None):
112 | """Loads saved model from file
113 |
114 | Args:
115 | save_path: Path to saved model (.pth). If a directory is provided instead, model-best.pth is used
116 | model: Torch model to restore weights to
117 | optimizer: Optimizer
118 | """
119 | if os.path.isdir(save_path):
120 | save_path = os.path.join(save_path, 'model-best.pth')
121 |
122 | state = torch.load(save_path)
123 |
124 | step = 0
125 | if 'step' in state:
126 | step = state['step']
127 |
128 | if 'state_dict' in state and model is not None:
129 | model.load_state_dict(state['state_dict'])
130 |
131 | if 'optimizer' in state and optimizer is not None:
132 | optimizer.load_state_dict(state['optimizer'])
133 |
134 | self._logger.info('Loaded models from {}'.format(save_path))
135 | return step
136 |
137 |
138 | class TorchDebugger(torch.autograd.detect_anomaly):
139 | """Enters debugger when anomaly detected"""
140 | def __enter__(self) -> None:
141 | super().__enter__()
142 |
143 | def __exit__(self, type, value, trace):
144 | super().__exit__()
145 | if isinstance(value, RuntimeError):
146 | traceback.print_tb(trace)
147 | print(value)
148 | if sys.gettrace() is None:
149 | pdb.set_trace()
150 |
--------------------------------------------------------------------------------
/configs/benchmarks/3DLoMatch/sun3d-hotel_umd-maryland_hotel3/gt_overlap.log:
--------------------------------------------------------------------------------
1 | 0,1,0.5325
2 | 0,2,0.0683
3 | 0,3,0.0000
4 | 0,4,0.0000
5 | 0,5,0.0000
6 | 0,6,0.0000
7 | 0,7,0.0000
8 | 0,8,0.0000
9 | 0,9,0.0000
10 | 0,10,0.0269
11 | 0,11,0.1804
12 | 0,12,0.3909
13 | 0,13,0.3089
14 | 0,14,0.0004
15 | 0,15,0.0000
16 | 0,16,0.0000
17 | 0,17,0.0000
18 | 0,18,0.0000
19 | 0,19,0.0000
20 | 0,20,0.0000
21 | 0,21,0.0000
22 | 0,22,0.0263
23 | 0,23,0.0105
24 | 0,24,0.0098
25 | 0,25,0.0002
26 | 0,26,0.0000
27 | 0,27,0.1104
28 | 0,28,0.0002
29 | 0,29,0.0000
30 | 0,30,0.0000
31 | 0,31,0.0000
32 | 0,32,0.0000
33 | 0,33,0.0000
34 | 0,34,0.0000
35 | 0,35,0.0000
36 | 0,36,0.0000
37 | 1,2,0.3132
38 | 1,3,0.0537
39 | 1,4,0.0000
40 | 1,5,0.0000
41 | 1,6,0.0000
42 | 1,7,0.0000
43 | 1,8,0.0000
44 | 1,9,0.0000
45 | 1,10,0.0000
46 | 1,11,0.1110
47 | 1,12,0.2444
48 | 1,13,0.1772
49 | 1,14,0.0000
50 | 1,15,0.0000
51 | 1,16,0.0000
52 | 1,17,0.0000
53 | 1,18,0.0000
54 | 1,19,0.0000
55 | 1,20,0.0000
56 | 1,21,0.0000
57 | 1,22,0.0000
58 | 1,23,0.0000
59 | 1,24,0.0000
60 | 1,25,0.0000
61 | 1,26,0.0000
62 | 1,27,0.0436
63 | 1,28,0.0000
64 | 1,29,0.0000
65 | 1,30,0.0000
66 | 1,31,0.0000
67 | 1,32,0.0000
68 | 1,33,0.0000
69 | 1,34,0.0000
70 | 1,35,0.0000
71 | 1,36,0.0000
72 | 2,3,0.4890
73 | 2,4,0.0686
74 | 2,5,0.0600
75 | 2,6,0.0000
76 | 2,7,0.0000
77 | 2,8,0.0000
78 | 2,9,0.0000
79 | 2,10,0.0000
80 | 2,11,0.0000
81 | 2,12,0.0000
82 | 2,13,0.0000
83 | 2,14,0.0000
84 | 2,15,0.0000
85 | 2,16,0.0000
86 | 2,17,0.0000
87 | 2,18,0.0000
88 | 2,19,0.0000
89 | 2,20,0.0000
90 | 2,21,0.0000
91 | 2,22,0.0000
92 | 2,23,0.0000
93 | 2,24,0.0000
94 | 2,25,0.0000
95 | 2,26,0.0000
96 | 2,27,0.0000
97 | 2,28,0.0000
98 | 2,29,0.0000
99 | 2,30,0.0000
100 | 2,31,0.0000
101 | 2,32,0.0000
102 | 2,33,0.0000
103 | 2,34,0.0000
104 | 2,35,0.0000
105 | 2,36,0.0000
106 | 3,4,0.5921
107 | 3,5,0.2586
108 | 3,6,0.0192
109 | 3,7,0.0000
110 | 3,8,0.0000
111 | 3,9,0.0000
112 | 3,10,0.0000
113 | 3,11,0.0000
114 | 3,12,0.0000
115 | 3,13,0.0000
116 | 3,14,0.0000
117 | 3,15,0.0000
118 | 3,16,0.0000
119 | 3,17,0.0000
120 | 3,18,0.0000
121 | 3,19,0.0000
122 | 3,20,0.0000
123 | 3,21,0.0000
124 | 3,22,0.0000
125 | 3,23,0.0000
126 | 3,24,0.0000
127 | 3,25,0.0000
128 | 3,26,0.0000
129 | 3,27,0.0000
130 | 3,28,0.0000
131 | 3,29,0.0000
132 | 3,30,0.0000
133 | 3,31,0.0000
134 | 3,32,0.0000
135 | 3,33,0.0000
136 | 3,34,0.0000
137 | 3,35,0.0000
138 | 3,36,0.0000
139 | 4,5,0.3325
140 | 4,6,0.0784
141 | 4,7,0.0000
142 | 4,8,0.0000
143 | 4,9,0.0000
144 | 4,10,0.0000
145 | 4,11,0.0000
146 | 4,12,0.0000
147 | 4,13,0.0000
148 | 4,14,0.0000
149 | 4,15,0.0000
150 | 4,16,0.0000
151 | 4,17,0.0000
152 | 4,18,0.0000
153 | 4,19,0.0000
154 | 4,20,0.0000
155 | 4,21,0.0000
156 | 4,22,0.0000
157 | 4,23,0.0000
158 | 4,24,0.0000
159 | 4,25,0.0000
160 | 4,26,0.0000
161 | 4,27,0.0000
162 | 4,28,0.0000
163 | 4,29,0.0000
164 | 4,30,0.0000
165 | 4,31,0.0000
166 | 4,32,0.0000
167 | 4,33,0.0000
168 | 4,34,0.0000
169 | 4,35,0.0000
170 | 4,36,0.0000
171 | 5,6,0.4993
172 | 5,7,0.1245
173 | 5,8,0.0000
174 | 5,9,0.0000
175 | 5,10,0.0000
176 | 5,11,0.0000
177 | 5,12,0.0000
178 | 5,13,0.0000
179 | 5,14,0.0000
180 | 5,15,0.0000
181 | 5,16,0.0000
182 | 5,17,0.0000
183 | 5,18,0.0000
184 | 5,19,0.0000
185 | 5,20,0.0000
186 | 5,21,0.0000
187 | 5,22,0.0000
188 | 5,23,0.0000
189 | 5,24,0.0000
190 | 5,25,0.0000
191 | 5,26,0.0000
192 | 5,27,0.0000
193 | 5,28,0.0000
194 | 5,29,0.0000
195 | 5,30,0.0000
196 | 5,31,0.0000
197 | 5,32,0.0000
198 | 5,33,0.0000
199 | 5,34,0.0000
200 | 5,35,0.0000
201 | 5,36,0.0000
202 | 6,7,0.4663
203 | 6,8,0.0432
204 | 6,9,0.0000
205 | 6,10,0.0000
206 | 6,11,0.0000
207 | 6,12,0.0000
208 | 6,13,0.0000
209 | 6,14,0.0000
210 | 6,15,0.0000
211 | 6,16,0.0000
212 | 6,17,0.0000
213 | 6,18,0.0000
214 | 6,19,0.0000
215 | 6,20,0.0000
216 | 6,21,0.0000
217 | 6,22,0.0000
218 | 6,23,0.0000
219 | 6,24,0.0000
220 | 6,25,0.0000
221 | 6,26,0.0000
222 | 6,27,0.0000
223 | 6,28,0.0000
224 | 6,29,0.0000
225 | 6,30,0.0000
226 | 6,31,0.0000
227 | 6,32,0.0000
228 | 6,33,0.0000
229 | 6,34,0.0000
230 | 6,35,0.0000
231 | 6,36,0.0000
232 | 7,8,0.3918
233 | 7,9,0.0272
234 | 7,10,0.0796
235 | 7,11,0.0000
236 | 7,12,0.0000
237 | 7,13,0.0000
238 | 7,14,0.0605
239 | 7,15,0.0651
240 | 7,16,0.0000
241 | 7,17,0.0000
242 | 7,18,0.0000
243 | 7,19,0.0000
244 | 7,20,0.0000
245 | 7,21,0.0000
246 | 7,22,0.0000
247 | 7,23,0.0000
248 | 7,24,0.0000
249 | 7,25,0.0000
250 | 7,26,0.0000
251 | 7,27,0.0000
252 | 7,28,0.0000
253 | 7,29,0.0000
254 | 7,30,0.0000
255 | 7,31,0.0000
256 | 7,32,0.0000
257 | 7,33,0.0000
258 | 7,34,0.0000
259 | 7,35,0.0000
260 | 7,36,0.0000
261 | 8,9,0.4565
262 | 8,10,0.3677
263 | 8,11,0.0000
264 | 8,12,0.0000
265 | 8,13,0.0000
266 | 8,14,0.1760
267 | 8,15,0.4993
268 | 8,16,0.2940
269 | 8,17,0.0577
270 | 8,18,0.0006
271 | 8,19,0.0000
272 | 8,20,0.0000
273 | 8,21,0.0000
274 | 8,22,0.0000
275 | 8,23,0.0000
276 | 8,24,0.0000
277 | 8,25,0.0000
278 | 8,26,0.0000
279 | 8,27,0.0000
280 | 8,28,0.0000
281 | 8,29,0.0000
282 | 8,30,0.0000
283 | 8,31,0.0000
284 | 8,32,0.0000
285 | 8,33,0.0000
286 | 8,34,0.0000
287 | 8,35,0.0000
288 | 8,36,0.0000
289 | 9,10,0.2301
290 | 9,11,0.0546
291 | 9,12,0.0000
292 | 9,13,0.0274
293 | 9,14,0.0741
294 | 9,15,0.2451
295 | 9,16,0.1903
296 | 9,17,0.0907
297 | 9,18,0.0404
298 | 9,19,0.0087
299 | 9,20,0.0000
300 | 9,21,0.0000
301 | 9,22,0.0000
302 | 9,23,0.0000
303 | 9,24,0.0000
304 | 9,25,0.0000
305 | 9,26,0.0000
306 | 9,27,0.0000
307 | 9,28,0.0000
308 | 9,29,0.0000
309 | 9,30,0.0000
310 | 9,31,0.0000
311 | 9,32,0.0000
312 | 9,33,0.0000
313 | 9,34,0.0000
314 | 9,35,0.0000
315 | 9,36,0.0000
316 | 10,11,0.2857
317 | 10,12,0.0900
318 | 10,13,0.1489
319 | 10,14,0.5227
320 | 10,15,0.5015
321 | 10,16,0.4256
322 | 10,17,0.2176
323 | 10,18,0.0341
324 | 10,19,0.0106
325 | 10,20,0.0000
326 | 10,21,0.0000
327 | 10,22,0.0000
328 | 10,23,0.0005
329 | 10,24,0.0018
330 | 10,25,0.0010
331 | 10,26,0.0000
332 | 10,27,0.0011
333 | 10,28,0.0007
334 | 10,29,0.0000
335 | 10,30,0.0000
336 | 10,31,0.0000
337 | 10,32,0.0000
338 | 10,33,0.0000
339 | 10,34,0.0000
340 | 10,35,0.0000
341 | 10,36,0.0000
342 | 11,12,0.6637
343 | 11,13,0.7383
344 | 11,14,0.2992
345 | 11,15,0.0000
346 | 11,16,0.0219
347 | 11,17,0.0121
348 | 11,18,0.0000
349 | 11,19,0.0000
350 | 11,20,0.0000
351 | 11,21,0.0006
352 | 11,22,0.0436
353 | 11,23,0.0238
354 | 11,24,0.0194
355 | 11,25,0.0047
356 | 11,26,0.0028
357 | 11,27,0.1267
358 | 11,28,0.0028
359 | 11,29,0.0000
360 | 11,30,0.0000
361 | 11,31,0.0000
362 | 11,32,0.0000
363 | 11,33,0.0000
364 | 11,34,0.0000
365 | 11,35,0.0000
366 | 11,36,0.0000
367 | 12,13,0.5171
368 | 12,14,0.0847
369 | 12,15,0.0000
370 | 12,16,0.0000
371 | 12,17,0.0000
372 | 12,18,0.0000
373 | 12,19,0.0000
374 | 12,20,0.0000
375 | 12,21,0.0008
376 | 12,22,0.0525
377 | 12,23,0.0422
378 | 12,24,0.0159
379 | 12,25,0.0030
380 | 12,26,0.0073
381 | 12,27,0.1169
382 | 12,28,0.0028
383 | 12,29,0.0093
384 | 12,30,0.0000
385 | 12,31,0.0000
386 | 12,32,0.0000
387 | 12,33,0.0000
388 | 12,34,0.0000
389 | 12,35,0.0000
390 | 12,36,0.0000
391 | 13,14,0.1723
392 | 13,15,0.0003
393 | 13,16,0.0000
394 | 13,17,0.0000
395 | 13,18,0.0000
396 | 13,19,0.0000
397 | 13,20,0.0000
398 | 13,21,0.0017
399 | 13,22,0.0478
400 | 13,23,0.0371
401 | 13,24,0.0210
402 | 13,25,0.0049
403 | 13,26,0.0000
404 | 13,27,0.1237
405 | 13,28,0.0030
406 | 13,29,0.0050
407 | 13,30,0.0000
408 | 13,31,0.0000
409 | 13,32,0.0000
410 | 13,33,0.0000
411 | 13,34,0.0000
412 | 13,35,0.0000
413 | 13,36,0.0000
414 | 14,15,0.3409
415 | 14,16,0.2692
416 | 14,17,0.2338
417 | 14,18,0.0061
418 | 14,19,0.0075
419 | 14,20,0.0079
420 | 14,21,0.0065
421 | 14,22,0.0011
422 | 14,23,0.0043
423 | 14,24,0.0063
424 | 14,25,0.0023
425 | 14,26,0.0000
426 | 14,27,0.0045
427 | 14,28,0.0027
428 | 14,29,0.0000
429 | 14,30,0.0000
430 | 14,31,0.0000
431 | 14,32,0.0000
432 | 14,33,0.0000
433 | 14,34,0.0000
434 | 14,35,0.0000
435 | 14,36,0.0002
436 | 15,16,0.6412
437 | 15,17,0.3784
438 | 15,18,0.0479
439 | 15,19,0.0572
440 | 15,20,0.0059
441 | 15,21,0.0000
442 | 15,22,0.0000
443 | 15,23,0.0000
444 | 15,24,0.0000
445 | 15,25,0.0000
446 | 15,26,0.0000
447 | 15,27,0.0000
448 | 15,28,0.0000
449 | 15,29,0.0000
450 | 15,30,0.0000
451 | 15,31,0.0000
452 | 15,32,0.0000
453 | 15,33,0.0000
454 | 15,34,0.0000
455 | 15,35,0.0000
456 | 15,36,0.0000
457 | 16,17,0.6605
458 | 16,18,0.1551
459 | 16,19,0.1564
460 | 16,20,0.0070
461 | 16,21,0.0037
462 | 16,22,0.0000
463 | 16,23,0.0000
464 | 16,24,0.0000
465 | 16,25,0.0000
466 | 16,26,0.0000
467 | 16,27,0.0000
468 | 16,28,0.0000
469 | 16,29,0.0000
470 | 16,30,0.0000
471 | 16,31,0.0000
472 | 16,32,0.0000
473 | 16,33,0.0000
474 | 16,34,0.0000
475 | 16,35,0.0003
476 | 16,36,0.0065
477 | 17,18,0.4449
478 | 17,19,0.5912
479 | 17,20,0.3402
480 | 17,21,0.0151
481 | 17,22,0.0000
482 | 17,23,0.0000
483 | 17,24,0.0000
484 | 17,25,0.0000
485 | 17,26,0.0000
486 | 17,27,0.0000
487 | 17,28,0.0000
488 | 17,29,0.0000
489 | 17,30,0.0000
490 | 17,31,0.0000
491 | 17,32,0.0000
492 | 17,33,0.0144
493 | 17,34,0.0610
494 | 17,35,0.0111
495 | 17,36,0.0755
496 | 18,19,0.5922
497 | 18,20,0.2836
498 | 18,21,0.0132
499 | 18,22,0.0000
500 | 18,23,0.0000
501 | 18,24,0.0000
502 | 18,25,0.0000
503 | 18,26,0.0000
504 | 18,27,0.0000
505 | 18,28,0.0000
506 | 18,29,0.0000
507 | 18,30,0.0000
508 | 18,31,0.0000
509 | 18,32,0.0000
510 | 18,33,0.0000
511 | 18,34,0.0055
512 | 18,35,0.0089
513 | 18,36,0.0382
514 | 19,20,0.4955
515 | 19,21,0.0496
516 | 19,22,0.0000
517 | 19,23,0.0000
518 | 19,24,0.0000
519 | 19,25,0.0000
520 | 19,26,0.0000
521 | 19,27,0.0000
522 | 19,28,0.0000
523 | 19,29,0.0000
524 | 19,30,0.0000
525 | 19,31,0.0000
526 | 19,32,0.0000
527 | 19,33,0.0274
528 | 19,34,0.0596
529 | 19,35,0.0140
530 | 19,36,0.0950
531 | 20,21,0.3810
532 | 20,22,0.0238
533 | 20,23,0.0040
534 | 20,24,0.0045
535 | 20,25,0.0010
536 | 20,26,0.0000
537 | 20,27,0.0045
538 | 20,28,0.0062
539 | 20,29,0.0000
540 | 20,30,0.0053
541 | 20,31,0.0576
542 | 20,32,0.0000
543 | 20,33,0.1121
544 | 20,34,0.1527
545 | 20,35,0.0143
546 | 20,36,0.1041
547 | 21,22,0.5275
548 | 21,23,0.3011
549 | 21,24,0.1952
550 | 21,25,0.0320
551 | 21,26,0.0016
552 | 21,27,0.0899
553 | 21,28,0.3441
554 | 21,29,0.2048
555 | 21,30,0.2257
556 | 21,31,0.2364
557 | 21,32,0.0316
558 | 21,33,0.0744
559 | 21,34,0.0670
560 | 21,35,0.0050
561 | 21,36,0.0172
562 | 22,23,0.7330
563 | 22,24,0.2303
564 | 22,25,0.0266
565 | 22,26,0.0267
566 | 22,27,0.1673
567 | 22,28,0.3191
568 | 22,29,0.4485
569 | 22,30,0.2956
570 | 22,31,0.1013
571 | 22,32,0.0161
572 | 22,33,0.0044
573 | 22,34,0.0085
574 | 22,35,0.0046
575 | 22,36,0.0075
576 | 23,24,0.2493
577 | 23,25,0.0259
578 | 23,26,0.0426
579 | 23,27,0.2199
580 | 23,28,0.3316
581 | 23,29,0.5661
582 | 23,30,0.3621
583 | 23,31,0.0670
584 | 23,32,0.0031
585 | 23,33,0.0000
586 | 23,34,0.0000
587 | 23,35,0.0000
588 | 23,36,0.0000
589 | 24,25,0.2683
590 | 24,26,0.0284
591 | 24,27,0.4720
592 | 24,28,0.6725
593 | 24,29,0.3175
594 | 24,30,0.1250
595 | 24,31,0.0131
596 | 24,32,0.0000
597 | 24,33,0.0000
598 | 24,34,0.0000
599 | 24,35,0.0000
600 | 24,36,0.0000
601 | 25,26,0.2499
602 | 25,27,0.4611
603 | 25,28,0.2101
604 | 25,29,0.0000
605 | 25,30,0.0000
606 | 25,31,0.0000
607 | 25,32,0.0000
608 | 25,33,0.0000
609 | 25,34,0.0000
610 | 25,35,0.0000
611 | 25,36,0.0000
612 | 26,27,0.7114
613 | 26,28,0.0033
614 | 26,29,0.0000
615 | 26,30,0.0000
616 | 26,31,0.0000
617 | 26,32,0.0000
618 | 26,33,0.0000
619 | 26,34,0.0000
620 | 26,35,0.0000
621 | 26,36,0.0000
622 | 27,28,0.1769
623 | 27,29,0.0335
624 | 27,30,0.0000
625 | 27,31,0.0000
626 | 27,32,0.0000
627 | 27,33,0.0000
628 | 27,34,0.0000
629 | 27,35,0.0000
630 | 27,36,0.0000
631 | 28,29,0.5445
632 | 28,30,0.3390
633 | 28,31,0.1712
634 | 28,32,0.0000
635 | 28,33,0.0000
636 | 28,34,0.0000
637 | 28,35,0.0000
638 | 28,36,0.0000
639 | 29,30,0.6915
640 | 29,31,0.1352
641 | 29,32,0.0507
642 | 29,33,0.0016
643 | 29,34,0.0000
644 | 29,35,0.0000
645 | 29,36,0.0000
646 | 30,31,0.4260
647 | 30,32,0.2778
648 | 30,33,0.1563
649 | 30,34,0.0450
650 | 30,35,0.0000
651 | 30,36,0.0080
652 | 31,32,0.4631
653 | 31,33,0.5335
654 | 31,34,0.3379
655 | 31,35,0.1129
656 | 31,36,0.2214
657 | 32,33,0.6403
658 | 32,34,0.3848
659 | 32,35,0.3697
660 | 32,36,0.3271
661 | 33,34,0.7574
662 | 33,35,0.3338
663 | 33,36,0.4225
664 | 34,35,0.4932
665 | 34,36,0.5212
666 | 35,36,0.5585
667 |
--------------------------------------------------------------------------------
/configs/benchmarks/3DMatch/sun3d-hotel_umd-maryland_hotel3/gt_overlap.log:
--------------------------------------------------------------------------------
1 | 0,1,0.5325
2 | 0,2,0.0683
3 | 0,3,0.0000
4 | 0,4,0.0000
5 | 0,5,0.0000
6 | 0,6,0.0000
7 | 0,7,0.0000
8 | 0,8,0.0000
9 | 0,9,0.0000
10 | 0,10,0.0269
11 | 0,11,0.1804
12 | 0,12,0.3909
13 | 0,13,0.3089
14 | 0,14,0.0004
15 | 0,15,0.0000
16 | 0,16,0.0000
17 | 0,17,0.0000
18 | 0,18,0.0000
19 | 0,19,0.0000
20 | 0,20,0.0000
21 | 0,21,0.0000
22 | 0,22,0.0263
23 | 0,23,0.0105
24 | 0,24,0.0098
25 | 0,25,0.0002
26 | 0,26,0.0000
27 | 0,27,0.1104
28 | 0,28,0.0002
29 | 0,29,0.0000
30 | 0,30,0.0000
31 | 0,31,0.0000
32 | 0,32,0.0000
33 | 0,33,0.0000
34 | 0,34,0.0000
35 | 0,35,0.0000
36 | 0,36,0.0000
37 | 1,2,0.3132
38 | 1,3,0.0537
39 | 1,4,0.0000
40 | 1,5,0.0000
41 | 1,6,0.0000
42 | 1,7,0.0000
43 | 1,8,0.0000
44 | 1,9,0.0000
45 | 1,10,0.0000
46 | 1,11,0.1110
47 | 1,12,0.2444
48 | 1,13,0.1772
49 | 1,14,0.0000
50 | 1,15,0.0000
51 | 1,16,0.0000
52 | 1,17,0.0000
53 | 1,18,0.0000
54 | 1,19,0.0000
55 | 1,20,0.0000
56 | 1,21,0.0000
57 | 1,22,0.0000
58 | 1,23,0.0000
59 | 1,24,0.0000
60 | 1,25,0.0000
61 | 1,26,0.0000
62 | 1,27,0.0436
63 | 1,28,0.0000
64 | 1,29,0.0000
65 | 1,30,0.0000
66 | 1,31,0.0000
67 | 1,32,0.0000
68 | 1,33,0.0000
69 | 1,34,0.0000
70 | 1,35,0.0000
71 | 1,36,0.0000
72 | 2,3,0.4890
73 | 2,4,0.0686
74 | 2,5,0.0600
75 | 2,6,0.0000
76 | 2,7,0.0000
77 | 2,8,0.0000
78 | 2,9,0.0000
79 | 2,10,0.0000
80 | 2,11,0.0000
81 | 2,12,0.0000
82 | 2,13,0.0000
83 | 2,14,0.0000
84 | 2,15,0.0000
85 | 2,16,0.0000
86 | 2,17,0.0000
87 | 2,18,0.0000
88 | 2,19,0.0000
89 | 2,20,0.0000
90 | 2,21,0.0000
91 | 2,22,0.0000
92 | 2,23,0.0000
93 | 2,24,0.0000
94 | 2,25,0.0000
95 | 2,26,0.0000
96 | 2,27,0.0000
97 | 2,28,0.0000
98 | 2,29,0.0000
99 | 2,30,0.0000
100 | 2,31,0.0000
101 | 2,32,0.0000
102 | 2,33,0.0000
103 | 2,34,0.0000
104 | 2,35,0.0000
105 | 2,36,0.0000
106 | 3,4,0.5921
107 | 3,5,0.2586
108 | 3,6,0.0192
109 | 3,7,0.0000
110 | 3,8,0.0000
111 | 3,9,0.0000
112 | 3,10,0.0000
113 | 3,11,0.0000
114 | 3,12,0.0000
115 | 3,13,0.0000
116 | 3,14,0.0000
117 | 3,15,0.0000
118 | 3,16,0.0000
119 | 3,17,0.0000
120 | 3,18,0.0000
121 | 3,19,0.0000
122 | 3,20,0.0000
123 | 3,21,0.0000
124 | 3,22,0.0000
125 | 3,23,0.0000
126 | 3,24,0.0000
127 | 3,25,0.0000
128 | 3,26,0.0000
129 | 3,27,0.0000
130 | 3,28,0.0000
131 | 3,29,0.0000
132 | 3,30,0.0000
133 | 3,31,0.0000
134 | 3,32,0.0000
135 | 3,33,0.0000
136 | 3,34,0.0000
137 | 3,35,0.0000
138 | 3,36,0.0000
139 | 4,5,0.3325
140 | 4,6,0.0784
141 | 4,7,0.0000
142 | 4,8,0.0000
143 | 4,9,0.0000
144 | 4,10,0.0000
145 | 4,11,0.0000
146 | 4,12,0.0000
147 | 4,13,0.0000
148 | 4,14,0.0000
149 | 4,15,0.0000
150 | 4,16,0.0000
151 | 4,17,0.0000
152 | 4,18,0.0000
153 | 4,19,0.0000
154 | 4,20,0.0000
155 | 4,21,0.0000
156 | 4,22,0.0000
157 | 4,23,0.0000
158 | 4,24,0.0000
159 | 4,25,0.0000
160 | 4,26,0.0000
161 | 4,27,0.0000
162 | 4,28,0.0000
163 | 4,29,0.0000
164 | 4,30,0.0000
165 | 4,31,0.0000
166 | 4,32,0.0000
167 | 4,33,0.0000
168 | 4,34,0.0000
169 | 4,35,0.0000
170 | 4,36,0.0000
171 | 5,6,0.4993
172 | 5,7,0.1245
173 | 5,8,0.0000
174 | 5,9,0.0000
175 | 5,10,0.0000
176 | 5,11,0.0000
177 | 5,12,0.0000
178 | 5,13,0.0000
179 | 5,14,0.0000
180 | 5,15,0.0000
181 | 5,16,0.0000
182 | 5,17,0.0000
183 | 5,18,0.0000
184 | 5,19,0.0000
185 | 5,20,0.0000
186 | 5,21,0.0000
187 | 5,22,0.0000
188 | 5,23,0.0000
189 | 5,24,0.0000
190 | 5,25,0.0000
191 | 5,26,0.0000
192 | 5,27,0.0000
193 | 5,28,0.0000
194 | 5,29,0.0000
195 | 5,30,0.0000
196 | 5,31,0.0000
197 | 5,32,0.0000
198 | 5,33,0.0000
199 | 5,34,0.0000
200 | 5,35,0.0000
201 | 5,36,0.0000
202 | 6,7,0.4663
203 | 6,8,0.0432
204 | 6,9,0.0000
205 | 6,10,0.0000
206 | 6,11,0.0000
207 | 6,12,0.0000
208 | 6,13,0.0000
209 | 6,14,0.0000
210 | 6,15,0.0000
211 | 6,16,0.0000
212 | 6,17,0.0000
213 | 6,18,0.0000
214 | 6,19,0.0000
215 | 6,20,0.0000
216 | 6,21,0.0000
217 | 6,22,0.0000
218 | 6,23,0.0000
219 | 6,24,0.0000
220 | 6,25,0.0000
221 | 6,26,0.0000
222 | 6,27,0.0000
223 | 6,28,0.0000
224 | 6,29,0.0000
225 | 6,30,0.0000
226 | 6,31,0.0000
227 | 6,32,0.0000
228 | 6,33,0.0000
229 | 6,34,0.0000
230 | 6,35,0.0000
231 | 6,36,0.0000
232 | 7,8,0.3918
233 | 7,9,0.0272
234 | 7,10,0.0796
235 | 7,11,0.0000
236 | 7,12,0.0000
237 | 7,13,0.0000
238 | 7,14,0.0605
239 | 7,15,0.0651
240 | 7,16,0.0000
241 | 7,17,0.0000
242 | 7,18,0.0000
243 | 7,19,0.0000
244 | 7,20,0.0000
245 | 7,21,0.0000
246 | 7,22,0.0000
247 | 7,23,0.0000
248 | 7,24,0.0000
249 | 7,25,0.0000
250 | 7,26,0.0000
251 | 7,27,0.0000
252 | 7,28,0.0000
253 | 7,29,0.0000
254 | 7,30,0.0000
255 | 7,31,0.0000
256 | 7,32,0.0000
257 | 7,33,0.0000
258 | 7,34,0.0000
259 | 7,35,0.0000
260 | 7,36,0.0000
261 | 8,9,0.4565
262 | 8,10,0.3677
263 | 8,11,0.0000
264 | 8,12,0.0000
265 | 8,13,0.0000
266 | 8,14,0.1760
267 | 8,15,0.4993
268 | 8,16,0.2940
269 | 8,17,0.0577
270 | 8,18,0.0006
271 | 8,19,0.0000
272 | 8,20,0.0000
273 | 8,21,0.0000
274 | 8,22,0.0000
275 | 8,23,0.0000
276 | 8,24,0.0000
277 | 8,25,0.0000
278 | 8,26,0.0000
279 | 8,27,0.0000
280 | 8,28,0.0000
281 | 8,29,0.0000
282 | 8,30,0.0000
283 | 8,31,0.0000
284 | 8,32,0.0000
285 | 8,33,0.0000
286 | 8,34,0.0000
287 | 8,35,0.0000
288 | 8,36,0.0000
289 | 9,10,0.2301
290 | 9,11,0.0546
291 | 9,12,0.0000
292 | 9,13,0.0274
293 | 9,14,0.0741
294 | 9,15,0.2451
295 | 9,16,0.1903
296 | 9,17,0.0907
297 | 9,18,0.0404
298 | 9,19,0.0087
299 | 9,20,0.0000
300 | 9,21,0.0000
301 | 9,22,0.0000
302 | 9,23,0.0000
303 | 9,24,0.0000
304 | 9,25,0.0000
305 | 9,26,0.0000
306 | 9,27,0.0000
307 | 9,28,0.0000
308 | 9,29,0.0000
309 | 9,30,0.0000
310 | 9,31,0.0000
311 | 9,32,0.0000
312 | 9,33,0.0000
313 | 9,34,0.0000
314 | 9,35,0.0000
315 | 9,36,0.0000
316 | 10,11,0.2857
317 | 10,12,0.0900
318 | 10,13,0.1489
319 | 10,14,0.5227
320 | 10,15,0.5015
321 | 10,16,0.4256
322 | 10,17,0.2176
323 | 10,18,0.0341
324 | 10,19,0.0106
325 | 10,20,0.0000
326 | 10,21,0.0000
327 | 10,22,0.0000
328 | 10,23,0.0005
329 | 10,24,0.0018
330 | 10,25,0.0010
331 | 10,26,0.0000
332 | 10,27,0.0011
333 | 10,28,0.0007
334 | 10,29,0.0000
335 | 10,30,0.0000
336 | 10,31,0.0000
337 | 10,32,0.0000
338 | 10,33,0.0000
339 | 10,34,0.0000
340 | 10,35,0.0000
341 | 10,36,0.0000
342 | 11,12,0.6637
343 | 11,13,0.7383
344 | 11,14,0.2992
345 | 11,15,0.0000
346 | 11,16,0.0219
347 | 11,17,0.0121
348 | 11,18,0.0000
349 | 11,19,0.0000
350 | 11,20,0.0000
351 | 11,21,0.0006
352 | 11,22,0.0436
353 | 11,23,0.0238
354 | 11,24,0.0194
355 | 11,25,0.0047
356 | 11,26,0.0028
357 | 11,27,0.1267
358 | 11,28,0.0028
359 | 11,29,0.0000
360 | 11,30,0.0000
361 | 11,31,0.0000
362 | 11,32,0.0000
363 | 11,33,0.0000
364 | 11,34,0.0000
365 | 11,35,0.0000
366 | 11,36,0.0000
367 | 12,13,0.5171
368 | 12,14,0.0847
369 | 12,15,0.0000
370 | 12,16,0.0000
371 | 12,17,0.0000
372 | 12,18,0.0000
373 | 12,19,0.0000
374 | 12,20,0.0000
375 | 12,21,0.0008
376 | 12,22,0.0525
377 | 12,23,0.0422
378 | 12,24,0.0159
379 | 12,25,0.0030
380 | 12,26,0.0073
381 | 12,27,0.1169
382 | 12,28,0.0028
383 | 12,29,0.0093
384 | 12,30,0.0000
385 | 12,31,0.0000
386 | 12,32,0.0000
387 | 12,33,0.0000
388 | 12,34,0.0000
389 | 12,35,0.0000
390 | 12,36,0.0000
391 | 13,14,0.1723
392 | 13,15,0.0003
393 | 13,16,0.0000
394 | 13,17,0.0000
395 | 13,18,0.0000
396 | 13,19,0.0000
397 | 13,20,0.0000
398 | 13,21,0.0017
399 | 13,22,0.0478
400 | 13,23,0.0371
401 | 13,24,0.0210
402 | 13,25,0.0049
403 | 13,26,0.0000
404 | 13,27,0.1237
405 | 13,28,0.0030
406 | 13,29,0.0050
407 | 13,30,0.0000
408 | 13,31,0.0000
409 | 13,32,0.0000
410 | 13,33,0.0000
411 | 13,34,0.0000
412 | 13,35,0.0000
413 | 13,36,0.0000
414 | 14,15,0.3409
415 | 14,16,0.2692
416 | 14,17,0.2338
417 | 14,18,0.0061
418 | 14,19,0.0075
419 | 14,20,0.0079
420 | 14,21,0.0065
421 | 14,22,0.0011
422 | 14,23,0.0043
423 | 14,24,0.0063
424 | 14,25,0.0023
425 | 14,26,0.0000
426 | 14,27,0.0045
427 | 14,28,0.0027
428 | 14,29,0.0000
429 | 14,30,0.0000
430 | 14,31,0.0000
431 | 14,32,0.0000
432 | 14,33,0.0000
433 | 14,34,0.0000
434 | 14,35,0.0000
435 | 14,36,0.0002
436 | 15,16,0.6412
437 | 15,17,0.3784
438 | 15,18,0.0479
439 | 15,19,0.0572
440 | 15,20,0.0059
441 | 15,21,0.0000
442 | 15,22,0.0000
443 | 15,23,0.0000
444 | 15,24,0.0000
445 | 15,25,0.0000
446 | 15,26,0.0000
447 | 15,27,0.0000
448 | 15,28,0.0000
449 | 15,29,0.0000
450 | 15,30,0.0000
451 | 15,31,0.0000
452 | 15,32,0.0000
453 | 15,33,0.0000
454 | 15,34,0.0000
455 | 15,35,0.0000
456 | 15,36,0.0000
457 | 16,17,0.6605
458 | 16,18,0.1551
459 | 16,19,0.1564
460 | 16,20,0.0070
461 | 16,21,0.0037
462 | 16,22,0.0000
463 | 16,23,0.0000
464 | 16,24,0.0000
465 | 16,25,0.0000
466 | 16,26,0.0000
467 | 16,27,0.0000
468 | 16,28,0.0000
469 | 16,29,0.0000
470 | 16,30,0.0000
471 | 16,31,0.0000
472 | 16,32,0.0000
473 | 16,33,0.0000
474 | 16,34,0.0000
475 | 16,35,0.0003
476 | 16,36,0.0065
477 | 17,18,0.4449
478 | 17,19,0.5912
479 | 17,20,0.3402
480 | 17,21,0.0151
481 | 17,22,0.0000
482 | 17,23,0.0000
483 | 17,24,0.0000
484 | 17,25,0.0000
485 | 17,26,0.0000
486 | 17,27,0.0000
487 | 17,28,0.0000
488 | 17,29,0.0000
489 | 17,30,0.0000
490 | 17,31,0.0000
491 | 17,32,0.0000
492 | 17,33,0.0144
493 | 17,34,0.0610
494 | 17,35,0.0111
495 | 17,36,0.0755
496 | 18,19,0.5922
497 | 18,20,0.2836
498 | 18,21,0.0132
499 | 18,22,0.0000
500 | 18,23,0.0000
501 | 18,24,0.0000
502 | 18,25,0.0000
503 | 18,26,0.0000
504 | 18,27,0.0000
505 | 18,28,0.0000
506 | 18,29,0.0000
507 | 18,30,0.0000
508 | 18,31,0.0000
509 | 18,32,0.0000
510 | 18,33,0.0000
511 | 18,34,0.0055
512 | 18,35,0.0089
513 | 18,36,0.0382
514 | 19,20,0.4955
515 | 19,21,0.0496
516 | 19,22,0.0000
517 | 19,23,0.0000
518 | 19,24,0.0000
519 | 19,25,0.0000
520 | 19,26,0.0000
521 | 19,27,0.0000
522 | 19,28,0.0000
523 | 19,29,0.0000
524 | 19,30,0.0000
525 | 19,31,0.0000
526 | 19,32,0.0000
527 | 19,33,0.0274
528 | 19,34,0.0596
529 | 19,35,0.0140
530 | 19,36,0.0950
531 | 20,21,0.3810
532 | 20,22,0.0238
533 | 20,23,0.0040
534 | 20,24,0.0045
535 | 20,25,0.0010
536 | 20,26,0.0000
537 | 20,27,0.0045
538 | 20,28,0.0062
539 | 20,29,0.0000
540 | 20,30,0.0053
541 | 20,31,0.0576
542 | 20,32,0.0000
543 | 20,33,0.1121
544 | 20,34,0.1527
545 | 20,35,0.0143
546 | 20,36,0.1041
547 | 21,22,0.5275
548 | 21,23,0.3011
549 | 21,24,0.1952
550 | 21,25,0.0320
551 | 21,26,0.0016
552 | 21,27,0.0899
553 | 21,28,0.3441
554 | 21,29,0.2048
555 | 21,30,0.2257
556 | 21,31,0.2364
557 | 21,32,0.0316
558 | 21,33,0.0744
559 | 21,34,0.0670
560 | 21,35,0.0050
561 | 21,36,0.0172
562 | 22,23,0.7330
563 | 22,24,0.2303
564 | 22,25,0.0266
565 | 22,26,0.0267
566 | 22,27,0.1673
567 | 22,28,0.3191
568 | 22,29,0.4485
569 | 22,30,0.2956
570 | 22,31,0.1013
571 | 22,32,0.0161
572 | 22,33,0.0044
573 | 22,34,0.0085
574 | 22,35,0.0046
575 | 22,36,0.0075
576 | 23,24,0.2493
577 | 23,25,0.0259
578 | 23,26,0.0426
579 | 23,27,0.2199
580 | 23,28,0.3316
581 | 23,29,0.5661
582 | 23,30,0.3621
583 | 23,31,0.0670
584 | 23,32,0.0031
585 | 23,33,0.0000
586 | 23,34,0.0000
587 | 23,35,0.0000
588 | 23,36,0.0000
589 | 24,25,0.2683
590 | 24,26,0.0284
591 | 24,27,0.4720
592 | 24,28,0.6725
593 | 24,29,0.3175
594 | 24,30,0.1250
595 | 24,31,0.0131
596 | 24,32,0.0000
597 | 24,33,0.0000
598 | 24,34,0.0000
599 | 24,35,0.0000
600 | 24,36,0.0000
601 | 25,26,0.2499
602 | 25,27,0.4611
603 | 25,28,0.2101
604 | 25,29,0.0000
605 | 25,30,0.0000
606 | 25,31,0.0000
607 | 25,32,0.0000
608 | 25,33,0.0000
609 | 25,34,0.0000
610 | 25,35,0.0000
611 | 25,36,0.0000
612 | 26,27,0.7114
613 | 26,28,0.0033
614 | 26,29,0.0000
615 | 26,30,0.0000
616 | 26,31,0.0000
617 | 26,32,0.0000
618 | 26,33,0.0000
619 | 26,34,0.0000
620 | 26,35,0.0000
621 | 26,36,0.0000
622 | 27,28,0.1769
623 | 27,29,0.0335
624 | 27,30,0.0000
625 | 27,31,0.0000
626 | 27,32,0.0000
627 | 27,33,0.0000
628 | 27,34,0.0000
629 | 27,35,0.0000
630 | 27,36,0.0000
631 | 28,29,0.5445
632 | 28,30,0.3390
633 | 28,31,0.1712
634 | 28,32,0.0000
635 | 28,33,0.0000
636 | 28,34,0.0000
637 | 28,35,0.0000
638 | 28,36,0.0000
639 | 29,30,0.6915
640 | 29,31,0.1352
641 | 29,32,0.0507
642 | 29,33,0.0016
643 | 29,34,0.0000
644 | 29,35,0.0000
645 | 29,36,0.0000
646 | 30,31,0.4260
647 | 30,32,0.2778
648 | 30,33,0.1563
649 | 30,34,0.0450
650 | 30,35,0.0000
651 | 30,36,0.0080
652 | 31,32,0.4631
653 | 31,33,0.5335
654 | 31,34,0.3379
655 | 31,35,0.1129
656 | 31,36,0.2214
657 | 32,33,0.6403
658 | 32,34,0.3848
659 | 32,35,0.3697
660 | 32,36,0.3271
661 | 33,34,0.7574
662 | 33,35,0.3338
663 | 33,36,0.4225
664 | 34,35,0.4932
665 | 34,36,0.5212
666 | 35,36,0.5585
667 |
--------------------------------------------------------------------------------
/configs/indoor/3DLoMatch.pkl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/configs/indoor/3DLoMatch.pkl
--------------------------------------------------------------------------------
/configs/indoor/3DMatch.pkl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/configs/indoor/3DMatch.pkl
--------------------------------------------------------------------------------
/configs/indoor/train_3dmatch.txt:
--------------------------------------------------------------------------------
1 | 7-scenes-chess
2 | 7-scenes-fire
3 | 7-scenes-office
4 | 7-scenes-pumpkin
5 | 7-scenes-stairs
6 | analysis-by-synthesis-apt1-kitchen
7 | analysis-by-synthesis-apt1-living
8 | analysis-by-synthesis-apt2-bed
9 | analysis-by-synthesis-apt2-kitchen
10 | analysis-by-synthesis-apt2-living
11 | analysis-by-synthesis-apt2-luke
12 | analysis-by-synthesis-office2-5a
13 | analysis-by-synthesis-office2-5b
14 | bundlefusion-apt0_1
15 | bundlefusion-apt0_2
16 | bundlefusion-apt0_3
17 | bundlefusion-apt0_4
18 | bundlefusion-apt1_1
19 | bundlefusion-apt1_2
20 | bundlefusion-apt1_3
21 | bundlefusion-apt1_4
22 | bundlefusion-apt2_1
23 | bundlefusion-apt2_2
24 | bundlefusion-copyroom_1
25 | bundlefusion-copyroom_2
26 | bundlefusion-office1_1
27 | bundlefusion-office1_2
28 | bundlefusion-office2
29 | bundlefusion-office3
30 | rgbd-scenes-v2-scene_01
31 | rgbd-scenes-v2-scene_02
32 | rgbd-scenes-v2-scene_03
33 | rgbd-scenes-v2-scene_04
34 | rgbd-scenes-v2-scene_05
35 | rgbd-scenes-v2-scene_06
36 | rgbd-scenes-v2-scene_07
37 | rgbd-scenes-v2-scene_08
38 | rgbd-scenes-v2-scene_09
39 | rgbd-scenes-v2-scene_11
40 | rgbd-scenes-v2-scene_12
41 | rgbd-scenes-v2-scene_13
42 | rgbd-scenes-v2-scene_14
43 | sun3d-brown_bm_1-brown_bm_1_1
44 | sun3d-brown_bm_1-brown_bm_1_2
45 | sun3d-brown_bm_1-brown_bm_1_3
46 | sun3d-brown_cogsci_1-brown_cogsci_1
47 | sun3d-brown_cs_2-brown_cs2_1
48 | sun3d-brown_cs_2-brown_cs2_2
49 | sun3d-brown_cs_3-brown_cs3
50 | sun3d-harvard_c3-hv_c3_1
51 | sun3d-harvard_c5-hv_c5_1
52 | sun3d-harvard_c6-hv_c6_1
53 | sun3d-harvard_c8-hv_c8_3
54 | sun3d-hotel_nips2012-nips_4_1
55 | sun3d-hotel_nips2012-nips_4_2
56 | sun3d-hotel_sf-scan1_1
57 | sun3d-hotel_sf-scan1_2
58 | sun3d-hotel_sf-scan1_3
59 | sun3d-hotel_sf-scan1_4
60 | sun3d-mit_32_d507-d507_2_1
61 | sun3d-mit_32_d507-d507_2_2
62 | sun3d-mit_46_ted_lab1-ted_lab_2_1
63 | sun3d-mit_46_ted_lab1-ted_lab_2_2
64 | sun3d-mit_46_ted_lab1-ted_lab_2_3
65 | sun3d-mit_46_ted_lab1-ted_lab_2_4
66 | sun3d-mit_76_417-76-417b_1
67 | sun3d-mit_76_417-76-417b_2_1
68 | sun3d-mit_76_417-76-417b_3
69 | sun3d-mit_76_417-76-417b_4
70 | sun3d-mit_76_417-76-417b_5
71 | sun3d-mit_dorm_next_sj-dorm_next_sj_oct_30_2012_scan1_erika
72 | sun3d-mit_w20_athena-sc_athena_oct_29_2012_scan1_erika_1
73 | sun3d-mit_w20_athena-sc_athena_oct_29_2012_scan1_erika_2
74 | sun3d-mit_w20_athena-sc_athena_oct_29_2012_scan1_erika_3
75 | sun3d-mit_w20_athena-sc_athena_oct_29_2012_scan1_erika_4
76 |
--------------------------------------------------------------------------------
/configs/indoor/train_info.pkl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/configs/indoor/train_info.pkl
--------------------------------------------------------------------------------
/configs/indoor/val_3dmatch.txt:
--------------------------------------------------------------------------------
1 | sun3d-brown_bm_4-brown_bm_4
2 | sun3d-harvard_c11-hv_c11_2
3 | 7-scenes-heads
4 | rgbd-scenes-v2-scene_10
5 | bundlefusion-office0_1
6 | bundlefusion-office0_2
7 | bundlefusion-office0_3
8 | analysis-by-synthesis-apt2-kitchen
9 |
--------------------------------------------------------------------------------
/configs/indoor/val_info.pkl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/prs-eth/OverlapPredator/8c78f125fc58d62ad7d149adf1fed43ed54937e4/configs/indoor/val_info.pkl
--------------------------------------------------------------------------------
/configs/kitti/test_kitti.txt:
--------------------------------------------------------------------------------
1 | 8
2 | 9
3 | 10
--------------------------------------------------------------------------------
/configs/kitti/train_kitti.txt:
--------------------------------------------------------------------------------
1 | 0
2 | 1
3 | 2
4 | 3
5 | 4
6 | 5
--------------------------------------------------------------------------------
/configs/kitti/val_kitti.txt:
--------------------------------------------------------------------------------
1 | 6
2 | 7
--------------------------------------------------------------------------------
/configs/modelnet/modelnet40_all.txt:
--------------------------------------------------------------------------------
1 | airplane
2 | bathtub
3 | bed
4 | bench
5 | bookshelf
6 | bottle
7 | bowl
8 | car
9 | chair
10 | cone
11 | cup
12 | curtain
13 | desk
14 | door
15 | dresser
16 | flower_pot
17 | glass_box
18 | guitar
19 | keyboard
20 | lamp
21 | laptop
22 | mantel
23 | monitor
24 | night_stand
25 | person
26 | piano
27 | plant
28 | radio
29 | range_hood
30 | sink
31 | sofa
32 | stairs
33 | stool
34 | table
35 | tent
36 | toilet
37 | tv_stand
38 | vase
39 | wardrobe
40 | xbox
41 |
--------------------------------------------------------------------------------
/configs/modelnet/modelnet40_half1.txt:
--------------------------------------------------------------------------------
1 | airplane
2 | bathtub
3 | bed
4 | bench
5 | bookshelf
6 | bottle
7 | bowl
8 | car
9 | chair
10 | cone
11 | cup
12 | curtain
13 | desk
14 | door
15 | dresser
16 | flower_pot
17 | glass_box
18 | guitar
19 | keyboard
20 | lamp
21 |
--------------------------------------------------------------------------------
/configs/modelnet/modelnet40_half2.txt:
--------------------------------------------------------------------------------
1 | laptop
2 | mantel
3 | monitor
4 | night_stand
5 | person
6 | piano
7 | plant
8 | radio
9 | range_hood
10 | sink
11 | sofa
12 | stairs
13 | stool
14 | table
15 | tent
16 | toilet
17 | tv_stand
18 | vase
19 | wardrobe
20 | xbox
21 |
--------------------------------------------------------------------------------
/configs/models.py:
--------------------------------------------------------------------------------
1 | architectures = dict()
2 | architectures['indoor'] = [
3 | 'simple',
4 | 'resnetb',
5 | 'resnetb_strided',
6 | 'resnetb',
7 | 'resnetb',
8 | 'resnetb_strided',
9 | 'resnetb',
10 | 'resnetb',
11 | 'resnetb_strided',
12 | 'resnetb',
13 | 'resnetb',
14 | 'nearest_upsample',
15 | 'unary',
16 | 'nearest_upsample',
17 | 'unary',
18 | 'nearest_upsample',
19 | 'last_unary'
20 | ]
21 |
22 | architectures['kitti'] = [
23 | 'simple',
24 | 'resnetb',
25 | 'resnetb_strided',
26 | 'resnetb',
27 | 'resnetb',
28 | 'resnetb_strided',
29 | 'resnetb',
30 | 'resnetb',
31 | 'resnetb_strided',
32 | 'resnetb',
33 | 'resnetb',
34 | 'nearest_upsample',
35 | 'unary',
36 | 'nearest_upsample',
37 | 'unary',
38 | 'nearest_upsample',
39 | 'last_unary'
40 | ]
41 |
42 | architectures['modelnet'] = [
43 | 'simple',
44 | 'resnetb',
45 | 'resnetb',
46 | 'resnetb_strided',
47 | 'resnetb',
48 | 'resnetb',
49 | 'resnetb_strided',
50 | 'resnetb',
51 | 'resnetb',
52 | 'nearest_upsample',
53 | 'unary',
54 | 'unary',
55 | 'nearest_upsample',
56 | 'unary',
57 | 'last_unary'
58 | ]
--------------------------------------------------------------------------------
/configs/test/indoor.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: indoor
3 | mode: test
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 1000
7 | snapshot_freq: 1
8 | pretrain: 'weights/indoor.pth'
9 |
10 |
11 | model:
12 | num_layers: 4
13 | in_points_dim: 3
14 | first_feats_dim: 128
15 | final_feats_dim: 32
16 | first_subsampling_dl: 0.025
17 | in_feats_dim: 1
18 | conv_radius: 2.5
19 | deform_radius: 5.0
20 | num_kernel_points: 15
21 | KP_extent: 2.0
22 | KP_influence: linear
23 | aggregation_mode: sum
24 | fixed_kernel_points: center
25 | use_batch_norm: True
26 | batch_norm_momentum: 0.02
27 | deformable: False
28 | modulated: False
29 | add_cross_score: True
30 | condition_feature: True
31 |
32 | overlap_attention_module:
33 | gnn_feats_dim: 256
34 | dgcnn_k: 10
35 | num_head: 4
36 | nets: ['self','cross','self']
37 |
38 | loss:
39 | pos_margin: 0.1
40 | neg_margin: 1.4
41 | log_scale: 24
42 | pos_radius: 0.0375
43 | safe_radius: 0.1
44 | overlap_radius: 0.0375
45 | matchability_radius: 0.05
46 | w_circle_loss: 1.0
47 | w_overlap_loss: 1.0
48 | w_saliency_loss: 0.0
49 | max_points: 256
50 |
51 | optimiser:
52 | optimizer: SGD
53 | max_epoch: 40
54 | lr: 0.005
55 | weight_decay: 0.000001
56 | momentum: 0.98
57 | scheduler: ExpLR
58 | scheduler_gamma: 0.95
59 | scheduler_freq: 1
60 | iter_size: 1
61 |
62 | dataset:
63 | dataset: indoor
64 | benchmark: 3DMatch
65 | root: data/indoor
66 | batch_size: 1
67 | num_workers: 6
68 | augment_noise: 0.005
69 | train_info: configs/indoor/train_info.pkl
70 | val_info: configs/indoor/val_info.pkl
71 |
72 | demo:
73 | src_pcd: assets/cloud_bin_21.pth
74 | tgt_pcd: assets/cloud_bin_34.pth
75 | n_points: 1000
76 |
77 |
--------------------------------------------------------------------------------
/configs/test/kitti.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: test
3 | mode: test
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 500
7 | snapshot_freq: 1
8 | pretrain: weights/kitti.pth
9 |
10 | model:
11 | num_layers: 4
12 | in_points_dim: 3
13 | first_feats_dim: 256
14 | final_feats_dim: 32
15 | first_subsampling_dl: 0.3
16 | in_feats_dim: 1
17 | conv_radius: 4.25
18 | deform_radius: 5.0
19 | num_kernel_points: 15
20 | KP_extent: 2.0
21 | KP_influence: linear
22 | aggregation_mode: sum
23 | fixed_kernel_points: center
24 | use_batch_norm: True
25 | batch_norm_momentum: 0.02
26 | deformable: False
27 | modulated: False
28 | add_cross_score: True
29 | condition_feature: True
30 |
31 | overlap_attention_module:
32 | gnn_feats_dim: 256
33 | dgcnn_k: 10
34 | num_head: 4
35 | nets: ['self','cross','self']
36 |
37 | loss:
38 | pos_margin: 0.1
39 | neg_margin: 1.4
40 | log_scale: 40
41 | pos_radius: 0.21
42 | safe_radius: 0.75
43 | overlap_radius: 0.45
44 | matchability_radius: 0.3
45 | w_circle_loss: 1.0
46 | w_overlap_loss: 1.0
47 | w_saliency_loss: 0.0
48 | max_points: 512
49 |
50 | optimiser:
51 | optimizer: SGD
52 | max_epoch: 150
53 | lr: 0.05
54 | weight_decay: 0.000001
55 | momentum: 0.98
56 | scheduler: ExpLR
57 | scheduler_gamma: 0.95
58 | scheduler_freq: 1
59 | iter_size: 1
60 |
61 | dataset:
62 | dataset: kitti
63 | benchmark: odometryKITTI
64 | root:
65 | batch_size: 1
66 | num_workers: 6
67 | augment_noise: 0.01
68 | augment_shift_range: 2.0
69 | augment_scale_max: 1.2
70 | augment_scale_min: 0.8
71 |
--------------------------------------------------------------------------------
/configs/test/modelnet.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: modelnet
3 | mode: test
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 1000
7 | snapshot_freq: 1
8 | pretrain: 'weights/modelnet.pth'
9 |
10 |
11 | model:
12 | num_layers: 3
13 | in_points_dim: 3
14 | first_feats_dim: 512
15 | final_feats_dim: 96
16 | first_subsampling_dl: 0.06
17 | in_feats_dim: 1
18 | conv_radius: 2.75
19 | deform_radius: 5.0
20 | num_kernel_points: 15
21 | KP_extent: 2.0
22 | KP_influence: linear
23 | aggregation_mode: sum
24 | fixed_kernel_points: center
25 | use_batch_norm: True
26 | batch_norm_momentum: 0.02
27 | deformable: False
28 | modulated: False
29 | add_cross_score: True
30 | condition_feature: True
31 |
32 | overlap_attention_module:
33 | gnn_feats_dim: 256
34 | dgcnn_k: 10
35 | num_head: 4
36 | nets: ['self','cross','self']
37 |
38 | loss:
39 | pos_margin: 0.1
40 | neg_margin: 1.4
41 | log_scale: 64
42 | pos_radius: 0.018
43 | safe_radius: 0.06
44 | overlap_radius: 0.04
45 | matchability_radius: 0.04
46 | w_circle_loss: 1.0
47 | w_overlap_loss: 1.0
48 | w_saliency_loss: 0.0
49 | max_points: 384
50 |
51 | optimiser:
52 | optimizer: SGD
53 | max_epoch: 200
54 | lr: 0.01
55 | weight_decay: 0.000001
56 | momentum: 0.98
57 | scheduler: ExpLR
58 | scheduler_gamma: 0.99
59 | scheduler_freq: 1
60 | iter_size: 4
61 |
62 | dataset:
63 | dataset: modelnet
64 | benchmark: modelnet
65 | root: data/modelnet40_ply_hdf5_2048
66 | batch_size: 1
67 | num_workers: 4
68 | augment_noise: 0.005
69 | train_categoryfile: configs/modelnet/modelnet40_half1.txt
70 | val_categoryfile: configs/modelnet/modelnet40_half1.txt
71 | test_categoryfile: configs/modelnet/modelnet40_half2.txt
72 | partial: [0.7,0.7] # set to [0.5, 0.5] for ModelLoNet
73 | num_points: 1024
74 | noise_type: crop
75 | rot_mag: 45.0
76 | trans_mag: 0.5
77 | dataset_type: modelnet_hdf
78 |
79 |
80 |
--------------------------------------------------------------------------------
/configs/train/indoor.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: indoor
3 | mode: train
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 1000
7 | snapshot_freq: 1
8 | pretrain: ''
9 |
10 |
11 | model:
12 | num_layers: 4
13 | in_points_dim: 3
14 | first_feats_dim: 128
15 | final_feats_dim: 32
16 | first_subsampling_dl: 0.025
17 | in_feats_dim: 1
18 | conv_radius: 2.5
19 | deform_radius: 5.0
20 | num_kernel_points: 15
21 | KP_extent: 2.0
22 | KP_influence: linear
23 | aggregation_mode: sum
24 | fixed_kernel_points: center
25 | use_batch_norm: True
26 | batch_norm_momentum: 0.02
27 | deformable: False
28 | modulated: False
29 | add_cross_score: True
30 | condition_feature: True
31 |
32 | overlap_attention_module:
33 | gnn_feats_dim: 256
34 | dgcnn_k: 10
35 | num_head: 4
36 | nets: ['self','cross','self']
37 |
38 | loss:
39 | pos_margin: 0.1
40 | neg_margin: 1.4
41 | log_scale: 24
42 | pos_radius: 0.0375
43 | safe_radius: 0.1
44 | overlap_radius: 0.0375
45 | matchability_radius: 0.05
46 | w_circle_loss: 1.0
47 | w_overlap_loss: 1.0
48 | w_saliency_loss: 0.0
49 | max_points: 256
50 |
51 | optimiser:
52 | optimizer: SGD
53 | max_epoch: 40
54 | lr: 0.005
55 | weight_decay: 0.000001
56 | momentum: 0.98
57 | scheduler: ExpLR
58 | scheduler_gamma: 0.95
59 | scheduler_freq: 1
60 | iter_size: 1
61 |
62 | dataset:
63 | dataset: indoor
64 | benchmark: 3DMatch
65 | root: data/indoor
66 | batch_size: 1
67 | num_workers: 6
68 | augment_noise: 0.005
69 | train_info: configs/indoor/train_info.pkl
70 | val_info: configs/indoor/val_info.pkl
71 |
72 | demo:
73 | src_pcd: assets/cloud_bin_21.pth
74 | tgt_pcd: assets/cloud_bin_34.pth
75 | n_points: 1000
76 |
77 |
--------------------------------------------------------------------------------
/configs/train/kitti.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: kitti
3 | mode: train
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 150
7 | snapshot_freq: 1
8 | pretrain: ''
9 |
10 | model:
11 | num_layers: 4
12 | in_points_dim: 3
13 | first_feats_dim: 256
14 | final_feats_dim: 32
15 | first_subsampling_dl: 0.3
16 | in_feats_dim: 1
17 | conv_radius: 4.25
18 | deform_radius: 5.0
19 | num_kernel_points: 15
20 | KP_extent: 2.0
21 | KP_influence: linear
22 | aggregation_mode: sum
23 | fixed_kernel_points: center
24 | use_batch_norm: True
25 | batch_norm_momentum: 0.02
26 | deformable: False
27 | modulated: False
28 | add_cross_score: True
29 | condition_feature: True
30 |
31 | overlap_attention_module:
32 | gnn_feats_dim: 256
33 | dgcnn_k: 10
34 | num_head: 4
35 | nets: ['self','cross','self']
36 |
37 | loss:
38 | pos_margin: 0.1
39 | neg_margin: 1.4
40 | log_scale: 48
41 | pos_radius: 0.21
42 | safe_radius: 0.75
43 | overlap_radius: 0.45
44 | matchability_radius: 0.3
45 | w_circle_loss: 1.0
46 | w_overlap_loss: 1.0
47 | w_saliency_loss: 0.0
48 | max_points: 512
49 |
50 | optimiser:
51 | optimizer: SGD
52 | max_epoch: 150
53 | lr: 0.05
54 | weight_decay: 0.000001
55 | momentum: 0.98
56 | scheduler: ExpLR
57 | scheduler_gamma: 0.99
58 | scheduler_freq: 1
59 | iter_size: 1
60 |
61 | dataset:
62 | dataset: kitti
63 | benchmark: odometryKITTI
64 | root:
65 | batch_size: 1
66 | num_workers: 6
67 | augment_noise: 0.01
68 | augment_shift_range: 2.0
69 | augment_scale_max: 1.2
70 | augment_scale_min: 0.8
71 |
--------------------------------------------------------------------------------
/configs/train/modelnet.yaml:
--------------------------------------------------------------------------------
1 | misc:
2 | exp_dir: modelnet
3 | mode: train
4 | gpu_mode: True
5 | verbose: True
6 | verbose_freq: 1000
7 | snapshot_freq: 1
8 | pretrain: ''
9 |
10 | model:
11 | num_layers: 3
12 | in_points_dim: 3
13 | first_feats_dim: 512
14 | final_feats_dim: 96
15 | first_subsampling_dl: 0.06
16 | in_feats_dim: 1
17 | conv_radius: 2.75
18 | deform_radius: 5.0
19 | num_kernel_points: 15
20 | KP_extent: 2.0
21 | KP_influence: linear
22 | aggregation_mode: sum
23 | fixed_kernel_points: center
24 | use_batch_norm: True
25 | batch_norm_momentum: 0.02
26 | deformable: False
27 | modulated: False
28 | add_cross_score: True
29 | condition_feature: True
30 |
31 | overlap_attention_module:
32 | gnn_feats_dim: 256
33 | dgcnn_k: 10
34 | num_head: 4
35 | nets: ['self','cross','self']
36 |
37 | loss:
38 | pos_margin: 0.1
39 | neg_margin: 1.4
40 | log_scale: 64
41 | pos_radius: 0.018
42 | safe_radius: 0.06
43 | overlap_radius: 0.04
44 | matchability_radius: 0.04
45 | w_circle_loss: 1.0
46 | w_overlap_loss: 1.0
47 | w_saliency_loss: 0.0
48 | max_points: 384
49 |
50 | optimiser:
51 | optimizer: SGD
52 | max_epoch: 200
53 | lr: 0.01
54 | weight_decay: 0.000001
55 | momentum: 0.98
56 | scheduler: ExpLR
57 | scheduler_gamma: 0.99
58 | scheduler_freq: 1
59 | iter_size: 4
60 |
61 | dataset:
62 | dataset: modelnet
63 | benchmark: modelnet
64 | root: data/modelnet40_ply_hdf5_2048
65 | batch_size: 1
66 | num_workers: 4
67 | augment_noise: 0.005
68 | train_categoryfile: configs/modelnet/modelnet40_half1.txt
69 | val_categoryfile: configs/modelnet/modelnet40_half1.txt
70 | test_categoryfile: configs/modelnet/modelnet40_half2.txt
71 | partial: [0.7,0.7]
72 | num_points: 1024
73 | noise_type: crop
74 | rot_mag: 45.0
75 | trans_mag: 0.5
76 | dataset_type: modelnet_hdf
77 |
78 |
79 |
--------------------------------------------------------------------------------
/cpp_wrappers/compile_wrappers.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 |
3 | # Compile cpp subsampling
4 | cd cpp_subsampling
5 | python3 setup.py build_ext --inplace
6 | cd ..
7 |
8 | # Compile cpp neighbors
9 | cd cpp_neighbors
10 | python3 setup.py build_ext --inplace
11 | cd ..
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_neighbors/build.bat:
--------------------------------------------------------------------------------
1 | @echo off
2 | py setup.py build_ext --inplace
3 |
4 |
5 | pause
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_neighbors/neighbors/neighbors.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include "neighbors.h"
3 |
4 |
5 | void brute_neighbors(vector& queries, vector& supports, vector& neighbors_indices, float radius, int verbose)
6 | {
7 |
8 | // Initialize variables
9 | // ******************
10 |
11 | // square radius
12 | float r2 = radius * radius;
13 |
14 | // indices
15 | int i0 = 0;
16 |
17 | // Counting vector
18 | int max_count = 0;
19 | vector> tmp(queries.size());
20 |
21 | // Search neigbors indices
22 | // ***********************
23 |
24 | for (auto& p0 : queries)
25 | {
26 | int i = 0;
27 | for (auto& p : supports)
28 | {
29 | if ((p0 - p).sq_norm() < r2)
30 | {
31 | tmp[i0].push_back(i);
32 | if (tmp[i0].size() > max_count)
33 | max_count = tmp[i0].size();
34 | }
35 | i++;
36 | }
37 | i0++;
38 | }
39 |
40 | // Reserve the memory
41 | neighbors_indices.resize(queries.size() * max_count);
42 | i0 = 0;
43 | for (auto& inds : tmp)
44 | {
45 | for (int j = 0; j < max_count; j++)
46 | {
47 | if (j < inds.size())
48 | neighbors_indices[i0 * max_count + j] = inds[j];
49 | else
50 | neighbors_indices[i0 * max_count + j] = -1;
51 | }
52 | i0++;
53 | }
54 |
55 | return;
56 | }
57 |
58 | void ordered_neighbors(vector& queries,
59 | vector& supports,
60 | vector& neighbors_indices,
61 | float radius)
62 | {
63 |
64 | // Initialize variables
65 | // ******************
66 |
67 | // square radius
68 | float r2 = radius * radius;
69 |
70 | // indices
71 | int i0 = 0;
72 |
73 | // Counting vector
74 | int max_count = 0;
75 | float d2;
76 | vector> tmp(queries.size());
77 | vector> dists(queries.size());
78 |
79 | // Search neigbors indices
80 | // ***********************
81 |
82 | for (auto& p0 : queries)
83 | {
84 | int i = 0;
85 | for (auto& p : supports)
86 | {
87 | d2 = (p0 - p).sq_norm();
88 | if (d2 < r2)
89 | {
90 | // Find order of the new point
91 | auto it = std::upper_bound(dists[i0].begin(), dists[i0].end(), d2);
92 | int index = std::distance(dists[i0].begin(), it);
93 |
94 | // Insert element
95 | dists[i0].insert(it, d2);
96 | tmp[i0].insert(tmp[i0].begin() + index, i);
97 |
98 | // Update max count
99 | if (tmp[i0].size() > max_count)
100 | max_count = tmp[i0].size();
101 | }
102 | i++;
103 | }
104 | i0++;
105 | }
106 |
107 | // Reserve the memory
108 | neighbors_indices.resize(queries.size() * max_count);
109 | i0 = 0;
110 | for (auto& inds : tmp)
111 | {
112 | for (int j = 0; j < max_count; j++)
113 | {
114 | if (j < inds.size())
115 | neighbors_indices[i0 * max_count + j] = inds[j];
116 | else
117 | neighbors_indices[i0 * max_count + j] = -1;
118 | }
119 | i0++;
120 | }
121 |
122 | return;
123 | }
124 |
125 | void batch_ordered_neighbors(vector& queries,
126 | vector& supports,
127 | vector& q_batches,
128 | vector& s_batches,
129 | vector& neighbors_indices,
130 | float radius)
131 | {
132 |
133 | // Initialize variables
134 | // ******************
135 |
136 | // square radius
137 | float r2 = radius * radius;
138 |
139 | // indices
140 | int i0 = 0;
141 |
142 | // Counting vector
143 | int max_count = 0;
144 | float d2;
145 | vector> tmp(queries.size());
146 | vector> dists(queries.size());
147 |
148 | // batch index
149 | int b = 0;
150 | int sum_qb = 0;
151 | int sum_sb = 0;
152 |
153 |
154 | // Search neigbors indices
155 | // ***********************
156 |
157 | for (auto& p0 : queries)
158 | {
159 | // Check if we changed batch
160 | if (i0 == sum_qb + q_batches[b])
161 | {
162 | sum_qb += q_batches[b];
163 | sum_sb += s_batches[b];
164 | b++;
165 | }
166 |
167 | // Loop only over the supports of current batch
168 | vector::iterator p_it;
169 | int i = 0;
170 | for(p_it = supports.begin() + sum_sb; p_it < supports.begin() + sum_sb + s_batches[b]; p_it++ )
171 | {
172 | d2 = (p0 - *p_it).sq_norm();
173 | if (d2 < r2)
174 | {
175 | // Find order of the new point
176 | auto it = std::upper_bound(dists[i0].begin(), dists[i0].end(), d2);
177 | int index = std::distance(dists[i0].begin(), it);
178 |
179 | // Insert element
180 | dists[i0].insert(it, d2);
181 | tmp[i0].insert(tmp[i0].begin() + index, sum_sb + i);
182 |
183 | // Update max count
184 | if (tmp[i0].size() > max_count)
185 | max_count = tmp[i0].size();
186 | }
187 | i++;
188 | }
189 | i0++;
190 | }
191 |
192 | // Reserve the memory
193 | neighbors_indices.resize(queries.size() * max_count);
194 | i0 = 0;
195 | for (auto& inds : tmp)
196 | {
197 | for (int j = 0; j < max_count; j++)
198 | {
199 | if (j < inds.size())
200 | neighbors_indices[i0 * max_count + j] = inds[j];
201 | else
202 | neighbors_indices[i0 * max_count + j] = supports.size();
203 | }
204 | i0++;
205 | }
206 |
207 | return;
208 | }
209 |
210 |
211 | void batch_nanoflann_neighbors(vector& queries,
212 | vector& supports,
213 | vector& q_batches,
214 | vector& s_batches,
215 | vector& neighbors_indices,
216 | float radius)
217 | {
218 |
219 | // Initialize variables
220 | // ******************
221 |
222 | // indices
223 | int i0 = 0;
224 |
225 | // Square radius
226 | float r2 = radius * radius;
227 |
228 | // Counting vector
229 | int max_count = 0;
230 | float d2;
231 | vector>> all_inds_dists(queries.size());
232 |
233 | // batch index
234 | int b = 0;
235 | int sum_qb = 0;
236 | int sum_sb = 0;
237 |
238 | // Nanoflann related variables
239 | // ***************************
240 |
241 | // CLoud variable
242 | PointCloud current_cloud;
243 |
244 | // Tree parameters
245 | nanoflann::KDTreeSingleIndexAdaptorParams tree_params(10 /* max leaf */);
246 |
247 | // KDTree type definition
248 | typedef nanoflann::KDTreeSingleIndexAdaptor< nanoflann::L2_Simple_Adaptor ,
249 | PointCloud,
250 | 3 > my_kd_tree_t;
251 |
252 | // Pointer to trees
253 | my_kd_tree_t* index;
254 |
255 | // Build KDTree for the first batch element
256 | current_cloud.pts = vector(supports.begin() + sum_sb, supports.begin() + sum_sb + s_batches[b]);
257 | index = new my_kd_tree_t(3, current_cloud, tree_params);
258 | index->buildIndex();
259 |
260 |
261 | // Search neigbors indices
262 | // ***********************
263 |
264 | // Search params
265 | nanoflann::SearchParams search_params;
266 | search_params.sorted = true;
267 |
268 | for (auto& p0 : queries)
269 | {
270 |
271 | // Check if we changed batch
272 | if (i0 == sum_qb + q_batches[b])
273 | {
274 | sum_qb += q_batches[b];
275 | sum_sb += s_batches[b];
276 | b++;
277 |
278 | // Change the points
279 | current_cloud.pts.clear();
280 | current_cloud.pts = vector(supports.begin() + sum_sb, supports.begin() + sum_sb + s_batches[b]);
281 |
282 | // Build KDTree of the current element of the batch
283 | delete index;
284 | index = new my_kd_tree_t(3, current_cloud, tree_params);
285 | index->buildIndex();
286 | }
287 |
288 | // Initial guess of neighbors size
289 | all_inds_dists[i0].reserve(max_count);
290 |
291 | // Find neighbors
292 | float query_pt[3] = { p0.x, p0.y, p0.z};
293 | size_t nMatches = index->radiusSearch(query_pt, r2, all_inds_dists[i0], search_params);
294 |
295 | // Update max count
296 | if (nMatches > max_count)
297 | max_count = nMatches;
298 |
299 | // Increment query idx
300 | i0++;
301 | }
302 |
303 | // Reserve the memory
304 | neighbors_indices.resize(queries.size() * max_count);
305 | i0 = 0;
306 | sum_sb = 0;
307 | sum_qb = 0;
308 | b = 0;
309 | for (auto& inds_dists : all_inds_dists)
310 | {
311 | // Check if we changed batch
312 | if (i0 == sum_qb + q_batches[b])
313 | {
314 | sum_qb += q_batches[b];
315 | sum_sb += s_batches[b];
316 | b++;
317 | }
318 |
319 | for (int j = 0; j < max_count; j++)
320 | {
321 | if (j < inds_dists.size())
322 | neighbors_indices[i0 * max_count + j] = inds_dists[j].first + sum_sb;
323 | else
324 | neighbors_indices[i0 * max_count + j] = supports.size();
325 | }
326 | i0++;
327 | }
328 |
329 | delete index;
330 |
331 | return;
332 | }
333 |
334 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_neighbors/neighbors/neighbors.h:
--------------------------------------------------------------------------------
1 |
2 |
3 | #include "../../cpp_utils/cloud/cloud.h"
4 | #include "../../cpp_utils/nanoflann/nanoflann.hpp"
5 |
6 | #include
7 | #include
8 |
9 | using namespace std;
10 |
11 |
12 | void ordered_neighbors(vector& queries,
13 | vector& supports,
14 | vector& neighbors_indices,
15 | float radius);
16 |
17 | void batch_ordered_neighbors(vector& queries,
18 | vector& supports,
19 | vector& q_batches,
20 | vector& s_batches,
21 | vector& neighbors_indices,
22 | float radius);
23 |
24 | void batch_nanoflann_neighbors(vector& queries,
25 | vector& supports,
26 | vector& q_batches,
27 | vector& s_batches,
28 | vector& neighbors_indices,
29 | float radius);
30 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_neighbors/setup.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup, Extension
2 | import numpy.distutils.misc_util
3 |
4 | # Adding OpenCV to project
5 | # ************************
6 |
7 | # Adding sources of the project
8 | # *****************************
9 |
10 | SOURCES = ["../cpp_utils/cloud/cloud.cpp",
11 | "neighbors/neighbors.cpp",
12 | "wrapper.cpp"]
13 |
14 | module = Extension(name="radius_neighbors",
15 | sources=SOURCES,
16 | extra_compile_args=['-std=c++11',
17 | '-D_GLIBCXX_USE_CXX11_ABI=0'])
18 |
19 |
20 | setup(ext_modules=[module], include_dirs=numpy.distutils.misc_util.get_numpy_include_dirs())
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_neighbors/wrapper.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include "neighbors/neighbors.h"
4 | #include
5 |
6 |
7 |
8 | // docstrings for our module
9 | // *************************
10 |
11 | static char module_docstring[] = "This module provides two methods to compute radius neighbors from pointclouds or batch of pointclouds";
12 |
13 | static char batch_query_docstring[] = "Method to get radius neighbors in a batch of stacked pointclouds";
14 |
15 |
16 | // Declare the functions
17 | // *********************
18 |
19 | static PyObject *batch_neighbors(PyObject *self, PyObject *args, PyObject *keywds);
20 |
21 |
22 | // Specify the members of the module
23 | // *********************************
24 |
25 | static PyMethodDef module_methods[] =
26 | {
27 | { "batch_query", (PyCFunction)batch_neighbors, METH_VARARGS | METH_KEYWORDS, batch_query_docstring },
28 | {NULL, NULL, 0, NULL}
29 | };
30 |
31 |
32 | // Initialize the module
33 | // *********************
34 |
35 | static struct PyModuleDef moduledef =
36 | {
37 | PyModuleDef_HEAD_INIT,
38 | "radius_neighbors", // m_name
39 | module_docstring, // m_doc
40 | -1, // m_size
41 | module_methods, // m_methods
42 | NULL, // m_reload
43 | NULL, // m_traverse
44 | NULL, // m_clear
45 | NULL, // m_free
46 | };
47 |
48 | PyMODINIT_FUNC PyInit_radius_neighbors(void)
49 | {
50 | import_array();
51 | return PyModule_Create(&moduledef);
52 | }
53 |
54 |
55 | // Definition of the batch_subsample method
56 | // **********************************
57 |
58 | static PyObject* batch_neighbors(PyObject* self, PyObject* args, PyObject* keywds)
59 | {
60 |
61 | // Manage inputs
62 | // *************
63 |
64 | // Args containers
65 | PyObject* queries_obj = NULL;
66 | PyObject* supports_obj = NULL;
67 | PyObject* q_batches_obj = NULL;
68 | PyObject* s_batches_obj = NULL;
69 |
70 | // Keywords containers
71 | static char* kwlist[] = { "queries", "supports", "q_batches", "s_batches", "radius", NULL };
72 | float radius = 0.1;
73 |
74 | // Parse the input
75 | if (!PyArg_ParseTupleAndKeywords(args, keywds, "OOOO|$f", kwlist, &queries_obj, &supports_obj, &q_batches_obj, &s_batches_obj, &radius))
76 | {
77 | PyErr_SetString(PyExc_RuntimeError, "Error parsing arguments");
78 | return NULL;
79 | }
80 |
81 |
82 | // Interpret the input objects as numpy arrays.
83 | PyObject* queries_array = PyArray_FROM_OTF(queries_obj, NPY_FLOAT, NPY_IN_ARRAY);
84 | PyObject* supports_array = PyArray_FROM_OTF(supports_obj, NPY_FLOAT, NPY_IN_ARRAY);
85 | PyObject* q_batches_array = PyArray_FROM_OTF(q_batches_obj, NPY_INT, NPY_IN_ARRAY);
86 | PyObject* s_batches_array = PyArray_FROM_OTF(s_batches_obj, NPY_INT, NPY_IN_ARRAY);
87 |
88 | // Verify data was load correctly.
89 | if (queries_array == NULL)
90 | {
91 | Py_XDECREF(queries_array);
92 | Py_XDECREF(supports_array);
93 | Py_XDECREF(q_batches_array);
94 | Py_XDECREF(s_batches_array);
95 | PyErr_SetString(PyExc_RuntimeError, "Error converting query points to numpy arrays of type float32");
96 | return NULL;
97 | }
98 | if (supports_array == NULL)
99 | {
100 | Py_XDECREF(queries_array);
101 | Py_XDECREF(supports_array);
102 | Py_XDECREF(q_batches_array);
103 | Py_XDECREF(s_batches_array);
104 | PyErr_SetString(PyExc_RuntimeError, "Error converting support points to numpy arrays of type float32");
105 | return NULL;
106 | }
107 | if (q_batches_array == NULL)
108 | {
109 | Py_XDECREF(queries_array);
110 | Py_XDECREF(supports_array);
111 | Py_XDECREF(q_batches_array);
112 | Py_XDECREF(s_batches_array);
113 | PyErr_SetString(PyExc_RuntimeError, "Error converting query batches to numpy arrays of type int32");
114 | return NULL;
115 | }
116 | if (s_batches_array == NULL)
117 | {
118 | Py_XDECREF(queries_array);
119 | Py_XDECREF(supports_array);
120 | Py_XDECREF(q_batches_array);
121 | Py_XDECREF(s_batches_array);
122 | PyErr_SetString(PyExc_RuntimeError, "Error converting support batches to numpy arrays of type int32");
123 | return NULL;
124 | }
125 |
126 | // Check that the input array respect the dims
127 | if ((int)PyArray_NDIM(queries_array) != 2 || (int)PyArray_DIM(queries_array, 1) != 3)
128 | {
129 | Py_XDECREF(queries_array);
130 | Py_XDECREF(supports_array);
131 | Py_XDECREF(q_batches_array);
132 | Py_XDECREF(s_batches_array);
133 | PyErr_SetString(PyExc_RuntimeError, "Wrong dimensions : query.shape is not (N, 3)");
134 | return NULL;
135 | }
136 | if ((int)PyArray_NDIM(supports_array) != 2 || (int)PyArray_DIM(supports_array, 1) != 3)
137 | {
138 | Py_XDECREF(queries_array);
139 | Py_XDECREF(supports_array);
140 | Py_XDECREF(q_batches_array);
141 | Py_XDECREF(s_batches_array);
142 | PyErr_SetString(PyExc_RuntimeError, "Wrong dimensions : support.shape is not (N, 3)");
143 | return NULL;
144 | }
145 | if ((int)PyArray_NDIM(q_batches_array) > 1)
146 | {
147 | Py_XDECREF(queries_array);
148 | Py_XDECREF(supports_array);
149 | Py_XDECREF(q_batches_array);
150 | Py_XDECREF(s_batches_array);
151 | PyErr_SetString(PyExc_RuntimeError, "Wrong dimensions : queries_batches.shape is not (B,) ");
152 | return NULL;
153 | }
154 | if ((int)PyArray_NDIM(s_batches_array) > 1)
155 | {
156 | Py_XDECREF(queries_array);
157 | Py_XDECREF(supports_array);
158 | Py_XDECREF(q_batches_array);
159 | Py_XDECREF(s_batches_array);
160 | PyErr_SetString(PyExc_RuntimeError, "Wrong dimensions : supports_batches.shape is not (B,) ");
161 | return NULL;
162 | }
163 | if ((int)PyArray_DIM(q_batches_array, 0) != (int)PyArray_DIM(s_batches_array, 0))
164 | {
165 | Py_XDECREF(queries_array);
166 | Py_XDECREF(supports_array);
167 | Py_XDECREF(q_batches_array);
168 | Py_XDECREF(s_batches_array);
169 | PyErr_SetString(PyExc_RuntimeError, "Wrong number of batch elements: different for queries and supports ");
170 | return NULL;
171 | }
172 |
173 | // Number of points
174 | int Nq = (int)PyArray_DIM(queries_array, 0);
175 | int Ns= (int)PyArray_DIM(supports_array, 0);
176 |
177 | // Number of batches
178 | int Nb = (int)PyArray_DIM(q_batches_array, 0);
179 |
180 | // Call the C++ function
181 | // *********************
182 |
183 | // Convert PyArray to Cloud C++ class
184 | vector queries;
185 | vector supports;
186 | vector q_batches;
187 | vector s_batches;
188 | queries = vector((PointXYZ*)PyArray_DATA(queries_array), (PointXYZ*)PyArray_DATA(queries_array) + Nq);
189 | supports = vector((PointXYZ*)PyArray_DATA(supports_array), (PointXYZ*)PyArray_DATA(supports_array) + Ns);
190 | q_batches = vector((int*)PyArray_DATA(q_batches_array), (int*)PyArray_DATA(q_batches_array) + Nb);
191 | s_batches = vector((int*)PyArray_DATA(s_batches_array), (int*)PyArray_DATA(s_batches_array) + Nb);
192 |
193 | // Create result containers
194 | vector neighbors_indices;
195 |
196 | // Compute results
197 | //batch_ordered_neighbors(queries, supports, q_batches, s_batches, neighbors_indices, radius);
198 | batch_nanoflann_neighbors(queries, supports, q_batches, s_batches, neighbors_indices, radius);
199 |
200 | // Check result
201 | if (neighbors_indices.size() < 1)
202 | {
203 | PyErr_SetString(PyExc_RuntimeError, "Error");
204 | return NULL;
205 | }
206 |
207 | // Manage outputs
208 | // **************
209 |
210 | // Maximal number of neighbors
211 | int max_neighbors = neighbors_indices.size() / Nq;
212 |
213 | // Dimension of output containers
214 | npy_intp* neighbors_dims = new npy_intp[2];
215 | neighbors_dims[0] = Nq;
216 | neighbors_dims[1] = max_neighbors;
217 |
218 | // Create output array
219 | PyObject* res_obj = PyArray_SimpleNew(2, neighbors_dims, NPY_INT);
220 | PyObject* ret = NULL;
221 |
222 | // Fill output array with values
223 | size_t size_in_bytes = Nq * max_neighbors * sizeof(int);
224 | memcpy(PyArray_DATA(res_obj), neighbors_indices.data(), size_in_bytes);
225 |
226 | // Merge results
227 | ret = Py_BuildValue("N", res_obj);
228 |
229 | // Clean up
230 | // ********
231 |
232 | Py_XDECREF(queries_array);
233 | Py_XDECREF(supports_array);
234 | Py_XDECREF(q_batches_array);
235 | Py_XDECREF(s_batches_array);
236 |
237 | return ret;
238 | }
239 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_subsampling/build.bat:
--------------------------------------------------------------------------------
1 | @echo off
2 | py setup.py build_ext --inplace
3 |
4 |
5 | pause
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_subsampling/grid_subsampling/grid_subsampling.cpp:
--------------------------------------------------------------------------------
1 |
2 | #include "grid_subsampling.h"
3 |
4 |
5 | void grid_subsampling(vector& original_points,
6 | vector& subsampled_points,
7 | vector& original_features,
8 | vector& subsampled_features,
9 | vector& original_classes,
10 | vector& subsampled_classes,
11 | float sampleDl,
12 | int verbose) {
13 |
14 | // Initialize variables
15 | // ******************
16 |
17 | // Number of points in the cloud
18 | size_t N = original_points.size();
19 |
20 | // Dimension of the features
21 | size_t fdim = original_features.size() / N;
22 | size_t ldim = original_classes.size() / N;
23 |
24 | // Limits of the cloud
25 | PointXYZ minCorner = min_point(original_points);
26 | PointXYZ maxCorner = max_point(original_points);
27 | PointXYZ originCorner = floor(minCorner * (1/sampleDl)) * sampleDl;
28 |
29 | // Dimensions of the grid
30 | size_t sampleNX = (size_t)floor((maxCorner.x - originCorner.x) / sampleDl) + 1;
31 | size_t sampleNY = (size_t)floor((maxCorner.y - originCorner.y) / sampleDl) + 1;
32 | //size_t sampleNZ = (size_t)floor((maxCorner.z - originCorner.z) / sampleDl) + 1;
33 |
34 | // Check if features and classes need to be processed
35 | bool use_feature = original_features.size() > 0;
36 | bool use_classes = original_classes.size() > 0;
37 |
38 |
39 | // Create the sampled map
40 | // **********************
41 |
42 | // Verbose parameters
43 | int i = 0;
44 | int nDisp = N / 100;
45 |
46 | // Initialize variables
47 | size_t iX, iY, iZ, mapIdx;
48 | unordered_map data;
49 |
50 | for (auto& p : original_points)
51 | {
52 | // Position of point in sample map
53 | iX = (size_t)floor((p.x - originCorner.x) / sampleDl);
54 | iY = (size_t)floor((p.y - originCorner.y) / sampleDl);
55 | iZ = (size_t)floor((p.z - originCorner.z) / sampleDl);
56 | mapIdx = iX + sampleNX*iY + sampleNX*sampleNY*iZ;
57 |
58 | // If not already created, create key
59 | if (data.count(mapIdx) < 1)
60 | data.emplace(mapIdx, SampledData(fdim, ldim));
61 |
62 | // Fill the sample map
63 | if (use_feature && use_classes)
64 | data[mapIdx].update_all(p, original_features.begin() + i * fdim, original_classes.begin() + i * ldim);
65 | else if (use_feature)
66 | data[mapIdx].update_features(p, original_features.begin() + i * fdim);
67 | else if (use_classes)
68 | data[mapIdx].update_classes(p, original_classes.begin() + i * ldim);
69 | else
70 | data[mapIdx].update_points(p);
71 |
72 | // Display
73 | i++;
74 | if (verbose > 1 && i%nDisp == 0)
75 | std::cout << "\rSampled Map : " << std::setw(3) << i / nDisp << "%";
76 |
77 | }
78 |
79 | // Divide for barycentre and transfer to a vector
80 | subsampled_points.reserve(data.size());
81 | if (use_feature)
82 | subsampled_features.reserve(data.size() * fdim);
83 | if (use_classes)
84 | subsampled_classes.reserve(data.size() * ldim);
85 | for (auto& v : data)
86 | {
87 | subsampled_points.push_back(v.second.point * (1.0 / v.second.count));
88 | if (use_feature)
89 | {
90 | float count = (float)v.second.count;
91 | transform(v.second.features.begin(),
92 | v.second.features.end(),
93 | v.second.features.begin(),
94 | [count](float f) { return f / count;});
95 | subsampled_features.insert(subsampled_features.end(),v.second.features.begin(),v.second.features.end());
96 | }
97 | if (use_classes)
98 | {
99 | for (int i = 0; i < ldim; i++)
100 | subsampled_classes.push_back(max_element(v.second.labels[i].begin(), v.second.labels[i].end(),
101 | [](const pair&a, const pair&b){return a.second < b.second;})->first);
102 | }
103 | }
104 |
105 | return;
106 | }
107 |
108 |
109 | void batch_grid_subsampling(vector& original_points,
110 | vector& subsampled_points,
111 | vector& original_features,
112 | vector& subsampled_features,
113 | vector& original_classes,
114 | vector& subsampled_classes,
115 | vector& original_batches,
116 | vector& subsampled_batches,
117 | float sampleDl,
118 | int max_p)
119 | {
120 | // Initialize variables
121 | // ******************
122 |
123 | int b = 0;
124 | int sum_b = 0;
125 |
126 | // Number of points in the cloud
127 | size_t N = original_points.size();
128 |
129 | // Dimension of the features
130 | size_t fdim = original_features.size() / N;
131 | size_t ldim = original_classes.size() / N;
132 |
133 | // Handle max_p = 0
134 | if (max_p < 1)
135 | max_p = N;
136 |
137 | // Loop over batches
138 | // *****************
139 |
140 | for (b = 0; b < original_batches.size(); b++)
141 | {
142 |
143 | // Extract batch points features and labels
144 | vector b_o_points = vector(original_points.begin () + sum_b,
145 | original_points.begin () + sum_b + original_batches[b]);
146 |
147 | vector b_o_features;
148 | if (original_features.size() > 0)
149 | {
150 | b_o_features = vector(original_features.begin () + sum_b * fdim,
151 | original_features.begin () + (sum_b + original_batches[b]) * fdim);
152 | }
153 |
154 | vector b_o_classes;
155 | if (original_classes.size() > 0)
156 | {
157 | b_o_classes = vector(original_classes.begin () + sum_b * ldim,
158 | original_classes.begin () + sum_b + original_batches[b] * ldim);
159 | }
160 |
161 |
162 | // Create result containers
163 | vector b_s_points;
164 | vector b_s_features;
165 | vector b_s_classes;
166 |
167 | // Compute subsampling on current batch
168 | grid_subsampling(b_o_points,
169 | b_s_points,
170 | b_o_features,
171 | b_s_features,
172 | b_o_classes,
173 | b_s_classes,
174 | sampleDl,
175 | 0);
176 |
177 | // Stack batches points features and labels
178 | // ****************************************
179 |
180 | // If too many points remove some
181 | if (b_s_points.size() <= max_p)
182 | {
183 | subsampled_points.insert(subsampled_points.end(), b_s_points.begin(), b_s_points.end());
184 |
185 | if (original_features.size() > 0)
186 | subsampled_features.insert(subsampled_features.end(), b_s_features.begin(), b_s_features.end());
187 |
188 | if (original_classes.size() > 0)
189 | subsampled_classes.insert(subsampled_classes.end(), b_s_classes.begin(), b_s_classes.end());
190 |
191 | subsampled_batches.push_back(b_s_points.size());
192 | }
193 | else
194 | {
195 | subsampled_points.insert(subsampled_points.end(), b_s_points.begin(), b_s_points.begin() + max_p);
196 |
197 | if (original_features.size() > 0)
198 | subsampled_features.insert(subsampled_features.end(), b_s_features.begin(), b_s_features.begin() + max_p * fdim);
199 |
200 | if (original_classes.size() > 0)
201 | subsampled_classes.insert(subsampled_classes.end(), b_s_classes.begin(), b_s_classes.begin() + max_p * ldim);
202 |
203 | subsampled_batches.push_back(max_p);
204 | }
205 |
206 | // Stack new batch lengths
207 | sum_b += original_batches[b];
208 | }
209 |
210 | return;
211 | }
212 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_subsampling/grid_subsampling/grid_subsampling.h:
--------------------------------------------------------------------------------
1 |
2 |
3 | #include "../../cpp_utils/cloud/cloud.h"
4 |
5 | #include
6 | #include
7 |
8 | using namespace std;
9 |
10 | class SampledData
11 | {
12 | public:
13 |
14 | // Elements
15 | // ********
16 |
17 | int count;
18 | PointXYZ point;
19 | vector features;
20 | vector> labels;
21 |
22 |
23 | // Methods
24 | // *******
25 |
26 | // Constructor
27 | SampledData()
28 | {
29 | count = 0;
30 | point = PointXYZ();
31 | }
32 |
33 | SampledData(const size_t fdim, const size_t ldim)
34 | {
35 | count = 0;
36 | point = PointXYZ();
37 | features = vector(fdim);
38 | labels = vector>(ldim);
39 | }
40 |
41 | // Method Update
42 | void update_all(const PointXYZ p, vector::iterator f_begin, vector::iterator l_begin)
43 | {
44 | count += 1;
45 | point += p;
46 | transform (features.begin(), features.end(), f_begin, features.begin(), plus());
47 | int i = 0;
48 | for(vector::iterator it = l_begin; it != l_begin + labels.size(); ++it)
49 | {
50 | labels[i][*it] += 1;
51 | i++;
52 | }
53 | return;
54 | }
55 | void update_features(const PointXYZ p, vector::iterator f_begin)
56 | {
57 | count += 1;
58 | point += p;
59 | transform (features.begin(), features.end(), f_begin, features.begin(), plus());
60 | return;
61 | }
62 | void update_classes(const PointXYZ p, vector::iterator l_begin)
63 | {
64 | count += 1;
65 | point += p;
66 | int i = 0;
67 | for(vector::iterator it = l_begin; it != l_begin + labels.size(); ++it)
68 | {
69 | labels[i][*it] += 1;
70 | i++;
71 | }
72 | return;
73 | }
74 | void update_points(const PointXYZ p)
75 | {
76 | count += 1;
77 | point += p;
78 | return;
79 | }
80 | };
81 |
82 | void grid_subsampling(vector& original_points,
83 | vector& subsampled_points,
84 | vector& original_features,
85 | vector& subsampled_features,
86 | vector& original_classes,
87 | vector& subsampled_classes,
88 | float sampleDl,
89 | int verbose);
90 |
91 | void batch_grid_subsampling(vector& original_points,
92 | vector& subsampled_points,
93 | vector& original_features,
94 | vector& subsampled_features,
95 | vector& original_classes,
96 | vector& subsampled_classes,
97 | vector& original_batches,
98 | vector& subsampled_batches,
99 | float sampleDl,
100 | int max_p);
101 |
102 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_subsampling/setup.py:
--------------------------------------------------------------------------------
1 | from distutils.core import setup, Extension
2 | import numpy.distutils.misc_util
3 |
4 | # Adding OpenCV to project
5 | # ************************
6 |
7 | # Adding sources of the project
8 | # *****************************
9 |
10 | SOURCES = ["../cpp_utils/cloud/cloud.cpp",
11 | "grid_subsampling/grid_subsampling.cpp",
12 | "wrapper.cpp"]
13 |
14 | module = Extension(name="grid_subsampling",
15 | sources=SOURCES,
16 | extra_compile_args=['-std=c++11',
17 | '-D_GLIBCXX_USE_CXX11_ABI=0'])
18 |
19 |
20 | setup(ext_modules=[module], include_dirs=numpy.distutils.misc_util.get_numpy_include_dirs())
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_utils/cloud/cloud.cpp:
--------------------------------------------------------------------------------
1 | //
2 | //
3 | // 0==========================0
4 | // | Local feature test |
5 | // 0==========================0
6 | //
7 | // version 1.0 :
8 | // >
9 | //
10 | //---------------------------------------------------
11 | //
12 | // Cloud source :
13 | // Define usefull Functions/Methods
14 | //
15 | //----------------------------------------------------
16 | //
17 | // Hugues THOMAS - 10/02/2017
18 | //
19 |
20 |
21 | #include "cloud.h"
22 |
23 |
24 | // Getters
25 | // *******
26 |
27 | PointXYZ max_point(std::vector points)
28 | {
29 | // Initialize limits
30 | PointXYZ maxP(points[0]);
31 |
32 | // Loop over all points
33 | for (auto p : points)
34 | {
35 | if (p.x > maxP.x)
36 | maxP.x = p.x;
37 |
38 | if (p.y > maxP.y)
39 | maxP.y = p.y;
40 |
41 | if (p.z > maxP.z)
42 | maxP.z = p.z;
43 | }
44 |
45 | return maxP;
46 | }
47 |
48 | PointXYZ min_point(std::vector points)
49 | {
50 | // Initialize limits
51 | PointXYZ minP(points[0]);
52 |
53 | // Loop over all points
54 | for (auto p : points)
55 | {
56 | if (p.x < minP.x)
57 | minP.x = p.x;
58 |
59 | if (p.y < minP.y)
60 | minP.y = p.y;
61 |
62 | if (p.z < minP.z)
63 | minP.z = p.z;
64 | }
65 |
66 | return minP;
67 | }
--------------------------------------------------------------------------------
/cpp_wrappers/cpp_utils/cloud/cloud.h:
--------------------------------------------------------------------------------
1 | //
2 | //
3 | // 0==========================0
4 | // | Local feature test |
5 | // 0==========================0
6 | //
7 | // version 1.0 :
8 | // >
9 | //
10 | //---------------------------------------------------
11 | //
12 | // Cloud header
13 | //
14 | //----------------------------------------------------
15 | //
16 | // Hugues THOMAS - 10/02/2017
17 | //
18 |
19 |
20 | # pragma once
21 |
22 | #include
23 | #include
24 | #include