Repository: hoangcuongbk80/Object-RPE Branch: iliad Commit: 0c8ed6da535f Files: 205 Total size: 1.5 MB Directory structure: gitextract_c4au6oyr/ ├── .gitignore ├── DenseFusion/ │ ├── LICENSE │ ├── README.md │ ├── datasets/ │ │ └── warehouse/ │ │ ├── dataset.py │ │ └── dataset_config/ │ │ ├── classes.txt │ │ ├── split_data.py │ │ ├── test_data_list.txt │ │ └── train_data_list.txt │ ├── docker/ │ │ ├── Dockerfile │ │ ├── docker_build.sh │ │ └── docker_run.sh │ ├── download.sh │ ├── experiments/ │ │ ├── logs/ │ │ │ └── warehouse/ │ │ │ └── note │ │ └── scripts/ │ │ ├── iliad.sh │ │ └── train_warehouse.sh │ ├── lib/ │ │ ├── extractors.py │ │ ├── knn/ │ │ │ ├── __init__.py │ │ │ ├── knn_pytorch.egg-info/ │ │ │ │ ├── PKG-INFO │ │ │ │ ├── SOURCES.txt │ │ │ │ ├── dependency_links.txt │ │ │ │ └── top_level.txt │ │ │ ├── knn_pytorch.py │ │ │ ├── setup.py │ │ │ └── src/ │ │ │ ├── cpu/ │ │ │ │ ├── knn_cpu.cpp │ │ │ │ └── vision.h │ │ │ ├── cuda/ │ │ │ │ ├── knn.cu │ │ │ │ └── vision.h │ │ │ ├── knn.h │ │ │ └── vision.cpp │ │ ├── loss.py │ │ ├── loss_refiner.py │ │ ├── network.py │ │ ├── pspnet.py │ │ ├── transformations.py │ │ └── utils.py │ ├── note.txt │ ├── tools/ │ │ ├── _init_paths.py │ │ ├── iliad.py │ │ └── train.py │ ├── trained_checkpoints/ │ │ └── warehouse/ │ │ └── note │ └── trained_models/ │ └── warehouse/ │ └── note ├── Mask_RCNN/ │ ├── LICENSE │ ├── MANIFEST.in │ ├── README.md │ ├── dataset_format │ ├── docker/ │ │ ├── Dockerfile │ │ ├── docker_build.sh │ │ └── docker_run.sh │ ├── mask_rcnn.egg-info/ │ │ ├── PKG-INFO │ │ ├── SOURCES.txt │ │ ├── dependency_links.txt │ │ └── top_level.txt │ ├── mrcnn/ │ │ ├── __init__.py │ │ ├── config.py │ │ ├── model.py │ │ ├── parallel_model.py │ │ ├── utils.py │ │ └── visualize.py │ ├── requirements.txt │ ├── samples/ │ │ └── warehouse/ │ │ ├── eval.py │ │ ├── iliad.py │ │ ├── note.txt │ │ └── train.py │ ├── setup.cfg │ └── setup.py ├── README.md └── obj_pose_est/ ├── CMakeLists.txt ├── include/ │ └── obj_pose_est/ │ ├── kalman_filter.h │ └── model_to_scene.h ├── launch/ │ ├── launch_iliad_cam.launch │ └── launch_iliad_rpe.launch ├── mapping/ │ ├── Core/ │ │ └── src/ │ │ ├── CMakeLists.txt │ │ ├── Cuda/ │ │ │ ├── containers/ │ │ │ │ ├── device_array.hpp │ │ │ │ ├── device_array_impl.hpp │ │ │ │ ├── device_memory.cpp │ │ │ │ ├── device_memory.hpp │ │ │ │ ├── device_memory_impl.hpp │ │ │ │ └── kernel_containers.hpp │ │ │ ├── convenience.cuh │ │ │ ├── cudafuncs.cu │ │ │ ├── cudafuncs.cuh │ │ │ ├── operators.cuh │ │ │ ├── reduce.cu │ │ │ └── types.cuh │ │ ├── CudaComputeTargetFlags.cmake │ │ ├── Defines.h │ │ ├── Deformation.cpp │ │ ├── Deformation.h │ │ ├── ElasticFusion.cpp │ │ ├── ElasticFusion.h │ │ ├── Ferns.cpp │ │ ├── Ferns.h │ │ ├── FindSuiteSparse.cmake │ │ ├── GPUTexture.cpp │ │ ├── GPUTexture.h │ │ ├── GlobalModel.cpp │ │ ├── GlobalModel.h │ │ ├── IndexMap.cpp │ │ ├── IndexMap.h │ │ ├── PoseMatch.h │ │ ├── Shaders/ │ │ │ ├── ComputePack.cpp │ │ │ ├── ComputePack.h │ │ │ ├── FeedbackBuffer.cpp │ │ │ ├── FeedbackBuffer.h │ │ │ ├── FillIn.cpp │ │ │ ├── FillIn.h │ │ │ ├── Resize.cpp │ │ │ ├── Resize.h │ │ │ ├── Shaders.h │ │ │ ├── Uniform.h │ │ │ ├── Vertex.cpp │ │ │ ├── Vertex.h │ │ │ ├── color.glsl │ │ │ ├── combo_splat.frag │ │ │ ├── copy_unstable.geom │ │ │ ├── copy_unstable.vert │ │ │ ├── data.frag │ │ │ ├── data.geom │ │ │ ├── data.vert │ │ │ ├── depth_bilateral.frag │ │ │ ├── depth_metric.frag │ │ │ ├── depth_norm.frag │ │ │ ├── depth_splat.frag │ │ │ ├── draw_feedback.frag │ │ │ ├── draw_feedback.vert │ │ │ ├── draw_global_surface.frag │ │ │ ├── draw_global_surface.geom │ │ │ ├── draw_global_surface.vert │ │ │ ├── draw_global_surface_phong.frag │ │ │ ├── empty.vert │ │ │ ├── fill_normal.frag │ │ │ ├── fill_rgb.frag │ │ │ ├── fill_vertex.frag │ │ │ ├── fxaa.frag │ │ │ ├── geometry.glsl │ │ │ ├── index_map.frag │ │ │ ├── index_map.vert │ │ │ ├── init_unstable.vert │ │ │ ├── quad.geom │ │ │ ├── resize.frag │ │ │ ├── sample.geom │ │ │ ├── sample.vert │ │ │ ├── splat.vert │ │ │ ├── surfels.glsl │ │ │ ├── update.vert │ │ │ ├── vertex_feedback.geom │ │ │ ├── vertex_feedback.vert │ │ │ └── visualise_textures.frag │ │ └── Utils/ │ │ ├── CholeskyDecomp.cpp │ │ ├── CholeskyDecomp.h │ │ ├── DeformationGraph.cpp │ │ ├── DeformationGraph.h │ │ ├── GPUConfig.h │ │ ├── GraphNode.h │ │ ├── Img.h │ │ ├── Intrinsics.cpp │ │ ├── Intrinsics.h │ │ ├── Jacobian.h │ │ ├── OdometryProvider.h │ │ ├── OrderedJacobianRow.h │ │ ├── Parse.cpp │ │ ├── Parse.h │ │ ├── RGBDOdometry.cpp │ │ ├── RGBDOdometry.h │ │ ├── Resolution.cpp │ │ ├── Resolution.h │ │ ├── Stopwatch.h │ │ ├── WindowsExtras.cpp │ │ └── WindowsExtras.h │ ├── LICENSE.txt │ ├── README.md │ ├── app/ │ │ ├── note │ │ └── src/ │ │ ├── CMakeLists.txt │ │ ├── FindBLAS.cmake │ │ ├── FindLAPACK.cmake │ │ ├── FindOpenNI2.cmake │ │ ├── FindRealSense.cmake │ │ ├── FindSuiteSparse.cmake │ │ ├── Findefusion.cmake │ │ ├── Main.cpp │ │ ├── MainController.cpp │ │ ├── MainController.h │ │ └── Tools/ │ │ ├── CameraInterface.h │ │ ├── GUI.h │ │ ├── GroundTruthOdometry.cpp │ │ ├── GroundTruthOdometry.h │ │ ├── JPEGLoader.h │ │ ├── LiveLogReader.cpp │ │ ├── LiveLogReader.h │ │ ├── LogReader.h │ │ ├── OpenNI2Interface.cpp │ │ ├── OpenNI2Interface.h │ │ ├── RawLogReader.cpp │ │ ├── RawLogReader.h │ │ ├── RealSenseInterface.cpp │ │ ├── RealSenseInterface.h │ │ └── ThreadMutexObject.h │ └── build.sh ├── package.xml ├── scripts/ │ └── ObjectRPE_srv.py ├── src/ │ ├── iliad_rpe_cam_node.cpp │ ├── iliad_rpe_node.cpp │ ├── kalman_filter.cpp │ └── model_to_scene.cpp └── srv/ └── ObjectRPE.srv ================================================ FILE CONTENTS ================================================ ================================================ FILE: .gitignore ================================================ # Data files and directories common data/ build/ dist/ *log.txt *.pth *.h5 # Byte-compiled / optimized / DLL files __pycache__/ *.py[cod] *$py.class # Distribution / packaging .Python env/ # Installer logs pip-log.txt pip-delete-this-directory.txt # VS Studio Code .vscode # PyCharm .idea/ # Dropbox .dropbox.attr # Jupyter Notebook .ipynb_checkpoints # pyenv .python-version # dotenv .env # virtualenv .venv venv/ ENV/ ================================================ FILE: DenseFusion/LICENSE ================================================ MIT License Copyright (c) 2019 Jeremy Wang Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ================================================ FILE: DenseFusion/README.md ================================================ # DenseFusion Based on the work of [Chen Wang](https://github.com/j96w/DenseFusion)
Modified by Dinh-Cuong Hoang ## Requirements * Python 3.5 * PyTorch 1.0 * torchvision 0.2.2.post3 * PIL * scipy * numpy * pyyaml * logging * cffi * matplotlib * Cython * CUDA 9.0/10.0 ```bash $ pip3 --no-cache-dir install numpy scipy pyyaml cffi pyyaml matplotlib Cython Pillow $ pip3 install https://download.pytorch.org/whl/cu100/torch-1.0.1.post2-cp35-cp35m-linux_x86_64.whl $ pip3 install torchvision==0.2.2.post3 ``` ## Train 1. To train ```bash sh /experiments/scripts/train_warehouse.sh ``` ================================================ FILE: DenseFusion/datasets/warehouse/dataset.py ================================================ import torch.utils.data as data from PIL import Image import os import os.path import torch import numpy as np import torchvision.transforms as transforms import argparse import time import random from lib.transformations import quaternion_from_euler, euler_matrix, random_quaternion, quaternion_matrix import numpy.ma as ma import copy import scipy.misc import scipy.io as scio class PoseDataset(data.Dataset): def __init__(self, mode, num_pt, add_noise, root, noise_trans, refine): if mode == 'train': self.path = 'datasets/warehouse/dataset_config/train_data_list.txt' elif mode == 'test': self.path = 'datasets/warehouse/dataset_config/test_data_list.txt' self.num_pt = num_pt self.root = root self.add_noise = add_noise self.noise_trans = noise_trans self.list = [] self.real = [] self.syn = [] input_file = open(self.path) while 1: input_line = input_file.readline() if not input_line: break if input_line[-1:] == '\n': input_line = input_line[:-1] if input_line[:5] == 'data/': self.real.append(input_line) else: self.syn.append(input_line) self.list.append(input_line) input_file.close() self.length = len(self.list) self.len_real = len(self.real) self.len_syn = len(self.syn) class_file = open('datasets/warehouse/dataset_config/classes.txt') class_id = 1 self.cld = {} while 1: class_input = class_file.readline() if not class_input: break input_file = open('{0}/models/{1}/points.xyz'.format(self.root, class_input[:-1])) self.cld[class_id] = [] while 1: input_line = input_file.readline() if not input_line: break input_line = input_line[:-1].split(' ') self.cld[class_id].append([float(input_line[0]), float(input_line[1]), float(input_line[2])]) self.cld[class_id] = np.array(self.cld[class_id]) input_file.close() class_id += 1 self.cam_cx_1 = 319.0000 self.cam_cy_1 = 237.0000 self.cam_fx_1 = 580.000 self.cam_fy_1 = 580.000 self.cam_cx_2 = 319.0000 self.cam_cy_2 = 237.0000 self.cam_fx_2 = 580.000 self.cam_fy_2 = 580.000 self.xmap = np.array([[j for i in range(640)] for j in range(480)]) self.ymap = np.array([[i for i in range(640)] for j in range(480)]) self.trancolor = transforms.ColorJitter(0.2, 0.2, 0.2, 0.05) self.noise_img_loc = 0.0 self.noise_img_scale = 7.0 self.minimum_num_pt = 50 self.norm = transforms.Normalize(mean=[0.485, 0.456, 0.406], std=[0.229, 0.224, 0.225]) #self.symmetry_obj_idx = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] self.symmetry_obj_idx = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13] self.num_pt_mesh_small = 500 self.num_pt_mesh_large = 2600 self.refine = refine self.front_num = 2 print(len(self.list)) def __getitem__(self, index): img = Image.open('{0}/{1}-color.png'.format(self.root, self.list[index])) depth = np.array(Image.open('{0}/{1}-depth.png'.format(self.root, self.list[index]))) label = np.array(Image.open('{0}/{1}-label.png'.format(self.root, self.list[index]))) meta = scio.loadmat('{0}/{1}-meta.mat'.format(self.root, self.list[index])) if self.list[index][:8] != 'data_syn' and int(self.list[index][5:9]) >= 60: cam_cx = self.cam_cx_2 cam_cy = self.cam_cy_2 cam_fx = self.cam_fx_2 cam_fy = self.cam_fy_2 else: cam_cx = self.cam_cx_1 cam_cy = self.cam_cy_1 cam_fx = self.cam_fx_1 cam_fy = self.cam_fy_1 mask_back = ma.getmaskarray(ma.masked_equal(label, 0)) add_front = False #Cuong We dont have synthetic data if len(self.syn) > 0: if self.add_noise: for k in range(5): seed = random.choice(self.syn) front = np.array(self.trancolor(Image.open('{0}/{1}-color.png'.format(self.root, seed)).convert("RGB"))) front = np.transpose(front, (2, 0, 1)) f_label = np.array(Image.open('{0}/{1}-label.png'.format(self.root, seed))) front_label = np.unique(f_label).tolist()[1:] if len(front_label) < self.front_num: continue front_label = random.sample(front_label, self.front_num) for f_i in front_label: mk = ma.getmaskarray(ma.masked_not_equal(f_label, f_i)) if f_i == front_label[0]: mask_front = mk else: mask_front = mask_front * mk t_label = label * mask_front if len(t_label.nonzero()[0]) > 1000: label = t_label add_front = True break obj = meta['cls_indexes'].flatten().astype(np.int32) while 1: idx = np.random.randint(0, len(obj)) mask_depth = ma.getmaskarray(ma.masked_not_equal(depth, 0)) mask_label = ma.getmaskarray(ma.masked_equal(label, obj[idx])) mask = mask_label * mask_depth if len(mask.nonzero()[0]) > self.minimum_num_pt: break if self.add_noise: img = self.trancolor(img) rmin, rmax, cmin, cmax = get_bbox(mask_label) img = np.transpose(np.array(img)[:, :, :3], (2, 0, 1))[:, rmin:rmax, cmin:cmax] if self.list[index][:8] == 'data_syn': seed = random.choice(self.real) back = np.array(self.trancolor(Image.open('{0}/{1}-color.png'.format(self.root, seed)).convert("RGB"))) back = np.transpose(back, (2, 0, 1))[:, rmin:rmax, cmin:cmax] img_masked = back * mask_back[rmin:rmax, cmin:cmax] + img else: img_masked = img if self.add_noise and add_front: img_masked = img_masked * mask_front[rmin:rmax, cmin:cmax] + front[:, rmin:rmax, cmin:cmax] * ~(mask_front[rmin:rmax, cmin:cmax]) if self.list[index][:8] == 'data_syn': img_masked = img_masked + np.random.normal(loc=0.0, scale=7.0, size=img_masked.shape) # p_img = np.transpose(img_masked, (1, 2, 0)) # scipy.misc.imsave('temp/{0}_input.png'.format(index), p_img) # scipy.misc.imsave('temp/{0}_label.png'.format(index), mask[rmin:rmax, cmin:cmax].astype(np.int32)) target_r = meta['poses'][:, :, idx][:, 0:3] target_t = np.array([meta['poses'][:, :, idx][:, 3:4].flatten()]) add_t = np.array([random.uniform(-self.noise_trans, self.noise_trans) for i in range(3)]) choose = mask[rmin:rmax, cmin:cmax].flatten().nonzero()[0] if len(choose) > self.num_pt: c_mask = np.zeros(len(choose), dtype=int) c_mask[:self.num_pt] = 1 np.random.shuffle(c_mask) choose = choose[c_mask.nonzero()] else: choose = np.pad(choose, (0, self.num_pt - len(choose)), 'wrap') depth_masked = depth[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) xmap_masked = self.xmap[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) ymap_masked = self.ymap[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) choose = np.array([choose]) cam_scale = meta['factor_depth'][0][0] pt2 = depth_masked / cam_scale pt0 = (ymap_masked - cam_cx) * pt2 / cam_fx pt1 = (xmap_masked - cam_cy) * pt2 / cam_fy cloud = np.concatenate((pt0, pt1, pt2), axis=1) if self.add_noise: cloud = np.add(cloud, add_t) # fw = open('temp/{0}_cld.xyz'.format(index), 'w') # for it in cloud: # fw.write('{0} {1} {2}\n'.format(it[0], it[1], it[2])) # fw.close() dellist = [j for j in range(0, len(self.cld[obj[idx]]))] if self.refine: dellist = random.sample(dellist, len(self.cld[obj[idx]]) - self.num_pt_mesh_large) else: dellist = random.sample(dellist, len(self.cld[obj[idx]]) - self.num_pt_mesh_small) model_points = np.delete(self.cld[obj[idx]], dellist, axis=0) # fw = open('temp/{0}_model_points.xyz'.format(index), 'w') # for it in model_points: # fw.write('{0} {1} {2}\n'.format(it[0], it[1], it[2])) # fw.close() target = np.dot(model_points, target_r.T) if self.add_noise: target = np.add(target, target_t + add_t) else: target = np.add(target, target_t) # fw = open('temp/{0}_tar.xyz'.format(index), 'w') # for it in target: # fw.write('{0} {1} {2}\n'.format(it[0], it[1], it[2])) # fw.close() return torch.from_numpy(cloud.astype(np.float32)), \ torch.LongTensor(choose.astype(np.int32)), \ self.norm(torch.from_numpy(img_masked.astype(np.float32))), \ torch.from_numpy(target.astype(np.float32)), \ torch.from_numpy(model_points.astype(np.float32)), \ torch.LongTensor([int(obj[idx]) - 1]) def __len__(self): return self.length def get_sym_list(self): return self.symmetry_obj_idx def get_num_points_mesh(self): if self.refine: return self.num_pt_mesh_large else: return self.num_pt_mesh_small border_list = [-1, 40, 80, 120, 160, 200, 240, 280, 320, 360, 400, 440, 480, 520, 560, 600, 640, 680] img_width = 480 img_length = 640 def get_bbox(label): rows = np.any(label, axis=1) cols = np.any(label, axis=0) rmin, rmax = np.where(rows)[0][[0, -1]] cmin, cmax = np.where(cols)[0][[0, -1]] rmax += 1 cmax += 1 r_b = rmax - rmin for tt in range(len(border_list)): if r_b > border_list[tt] and r_b < border_list[tt + 1]: r_b = border_list[tt + 1] break c_b = cmax - cmin for tt in range(len(border_list)): if c_b > border_list[tt] and c_b < border_list[tt + 1]: c_b = border_list[tt + 1] break center = [int((rmin + rmax) / 2), int((cmin + cmax) / 2)] rmin = center[0] - int(r_b / 2) rmax = center[0] + int(r_b / 2) cmin = center[1] - int(c_b / 2) cmax = center[1] + int(c_b / 2) if rmin < 0: delt = -rmin rmin = 0 rmax += delt if cmin < 0: delt = -cmin cmin = 0 cmax += delt if rmax > img_width: delt = rmax - img_width rmax = img_width rmin -= delt if cmax > img_length: delt = cmax - img_length cmax = img_length cmin -= delt return rmin, rmax, cmin, cmax ================================================ FILE: DenseFusion/datasets/warehouse/dataset_config/classes.txt ================================================ pallet_free half_pallet_free pallet_occluded half_pallet_occluded jacky frasvaf onos pauluns risi_frutti skansk sotstark tomatpure small_jacky ================================================ FILE: DenseFusion/datasets/warehouse/dataset_config/split_data.py ================================================ import glob f_test = open("test_data_list.txt", 'w') f_train = open("train_data_list.txt", 'w') test = ['0003', '0011', '0017', '0025', '0039'] val = ['0010','0018', '0026', '0027', '0028', '0029', '0030', '0031', '0032',] for i in range(0, 40): seq = 10000 + i seq_str = str(seq)[1:] data_dir = 'data/' + seq_str + '/' label_path = '/media/aass/783de628-b7ff-4217-8c96-7f3764de70d9/Warehouse_Dataset/' + data_dir label_addrs = glob.glob(label_path + '*-label.png') if seq_str in val: continue if seq_str in test: for j in range(0, len(label_addrs)): img_index = 1000000 + j + 1 img_index_str = str(img_index)[1:] img_dir = data_dir + img_index_str f_test.write(img_dir) f_test.write('\n') else: for j in range(0, len(label_addrs)): img_index = 1000000 + j +1 img_index_str = str(img_index)[1:] img_dir = data_dir + img_index_str f_train.write(img_dir) f_train.write('\n') ================================================ FILE: DenseFusion/datasets/warehouse/dataset_config/test_data_list.txt ================================================ data/0003/000001 data/0003/000002 data/0003/000003 data/0003/000004 data/0003/000005 data/0003/000006 data/0003/000007 data/0003/000008 data/0003/000009 data/0003/000010 data/0003/000011 data/0003/000012 data/0003/000013 data/0003/000014 data/0003/000015 data/0003/000016 data/0003/000017 data/0003/000018 data/0003/000019 data/0003/000020 data/0003/000021 data/0003/000022 data/0003/000023 data/0003/000024 data/0003/000025 data/0003/000026 data/0003/000027 data/0003/000028 data/0003/000029 data/0003/000030 data/0003/000031 data/0003/000032 data/0003/000033 data/0003/000034 data/0003/000035 data/0003/000036 data/0003/000037 data/0003/000038 data/0003/000039 data/0003/000040 data/0003/000041 data/0003/000042 data/0003/000043 data/0003/000044 data/0003/000045 data/0003/000046 data/0003/000047 data/0003/000048 data/0003/000049 data/0003/000050 data/0003/000051 data/0003/000052 data/0003/000053 data/0003/000054 data/0003/000055 data/0003/000056 data/0003/000057 data/0003/000058 data/0003/000059 data/0003/000060 data/0003/000061 data/0003/000062 data/0003/000063 data/0003/000064 data/0003/000065 data/0003/000066 data/0003/000067 data/0003/000068 data/0003/000069 data/0003/000070 data/0003/000071 data/0003/000072 data/0003/000073 data/0003/000074 data/0003/000075 data/0003/000076 data/0003/000077 data/0003/000078 data/0003/000079 data/0003/000080 data/0003/000081 data/0003/000082 data/0003/000083 data/0003/000084 data/0003/000085 data/0003/000086 data/0003/000087 data/0003/000088 data/0003/000089 data/0003/000090 data/0003/000091 data/0003/000092 data/0003/000093 data/0003/000094 data/0003/000095 data/0003/000096 data/0003/000097 data/0003/000098 data/0003/000099 data/0003/000100 data/0003/000101 data/0003/000102 data/0003/000103 data/0003/000104 data/0003/000105 data/0003/000106 data/0003/000107 data/0003/000108 data/0003/000109 data/0003/000110 data/0003/000111 data/0003/000112 data/0003/000113 data/0003/000114 data/0003/000115 data/0003/000116 data/0003/000117 data/0003/000118 data/0003/000119 data/0003/000120 data/0003/000121 data/0003/000122 data/0003/000123 data/0003/000124 data/0003/000125 data/0003/000126 data/0003/000127 data/0003/000128 data/0003/000129 data/0003/000130 data/0003/000131 data/0003/000132 data/0003/000133 data/0003/000134 data/0003/000135 data/0003/000136 data/0003/000137 data/0003/000138 data/0003/000139 data/0003/000140 data/0003/000141 data/0003/000142 data/0003/000143 data/0003/000144 data/0003/000145 data/0003/000146 data/0003/000147 data/0003/000148 data/0003/000149 data/0003/000150 data/0003/000151 data/0003/000152 data/0003/000153 data/0003/000154 data/0003/000155 data/0003/000156 data/0003/000157 data/0003/000158 data/0003/000159 data/0003/000160 data/0003/000161 data/0003/000162 data/0003/000163 data/0003/000164 data/0003/000165 data/0003/000166 data/0003/000167 data/0003/000168 data/0003/000169 data/0003/000170 data/0003/000171 data/0003/000172 data/0003/000173 data/0003/000174 data/0003/000175 data/0003/000176 data/0003/000177 data/0003/000178 data/0003/000179 data/0003/000180 data/0003/000181 data/0003/000182 data/0003/000183 data/0003/000184 data/0003/000185 data/0003/000186 data/0003/000187 data/0003/000188 data/0003/000189 data/0003/000190 data/0003/000191 data/0003/000192 data/0003/000193 data/0003/000194 data/0003/000195 data/0003/000196 data/0003/000197 data/0003/000198 data/0003/000199 data/0003/000200 data/0003/000201 data/0003/000202 data/0003/000203 data/0003/000204 data/0003/000205 data/0003/000206 data/0003/000207 data/0003/000208 data/0003/000209 data/0003/000210 data/0003/000211 data/0003/000212 data/0003/000213 data/0003/000214 data/0003/000215 data/0003/000216 data/0003/000217 data/0003/000218 data/0003/000219 data/0003/000220 data/0003/000221 data/0003/000222 data/0003/000223 data/0003/000224 data/0003/000225 data/0003/000226 data/0003/000227 data/0003/000228 data/0003/000229 data/0003/000230 data/0003/000231 data/0003/000232 data/0003/000233 data/0003/000234 data/0003/000235 data/0003/000236 data/0003/000237 data/0003/000238 data/0003/000239 data/0003/000240 data/0003/000241 data/0003/000242 data/0003/000243 data/0003/000244 data/0003/000245 data/0003/000246 data/0003/000247 data/0003/000248 data/0003/000249 data/0003/000250 data/0003/000251 data/0003/000252 data/0003/000253 data/0003/000254 data/0003/000255 data/0003/000256 data/0003/000257 data/0003/000258 data/0003/000259 data/0003/000260 data/0003/000261 data/0003/000262 data/0003/000263 data/0003/000264 data/0003/000265 data/0003/000266 data/0003/000267 data/0003/000268 data/0003/000269 data/0003/000270 data/0003/000271 data/0003/000272 data/0003/000273 data/0003/000274 data/0003/000275 data/0003/000276 data/0003/000277 data/0003/000278 data/0003/000279 data/0003/000280 data/0003/000281 data/0003/000282 data/0003/000283 data/0003/000284 data/0003/000285 data/0003/000286 data/0003/000287 data/0003/000288 data/0003/000289 data/0003/000290 data/0003/000291 data/0003/000292 data/0003/000293 data/0003/000294 data/0003/000295 data/0003/000296 data/0003/000297 data/0003/000298 data/0003/000299 data/0003/000300 data/0003/000301 data/0003/000302 data/0003/000303 data/0003/000304 data/0003/000305 data/0003/000306 data/0003/000307 data/0003/000308 data/0003/000309 data/0003/000310 data/0003/000311 data/0003/000312 data/0003/000313 data/0003/000314 data/0003/000315 data/0003/000316 data/0003/000317 data/0003/000318 data/0003/000319 data/0003/000320 data/0003/000321 data/0003/000322 data/0003/000323 data/0003/000324 data/0003/000325 data/0003/000326 data/0003/000327 data/0003/000328 data/0003/000329 data/0003/000330 data/0003/000331 data/0003/000332 data/0003/000333 data/0003/000334 data/0003/000335 data/0003/000336 data/0003/000337 data/0003/000338 data/0003/000339 data/0003/000340 data/0003/000341 data/0003/000342 data/0003/000343 data/0003/000344 data/0003/000345 data/0003/000346 data/0003/000347 data/0003/000348 data/0003/000349 data/0003/000350 data/0003/000351 data/0003/000352 data/0003/000353 data/0003/000354 data/0003/000355 data/0003/000356 data/0003/000357 data/0003/000358 data/0003/000359 data/0003/000360 data/0003/000361 data/0003/000362 data/0003/000363 data/0003/000364 data/0003/000365 data/0003/000366 data/0003/000367 data/0003/000368 data/0003/000369 data/0003/000370 data/0003/000371 data/0003/000372 data/0003/000373 data/0003/000374 data/0003/000375 data/0003/000376 data/0003/000377 data/0003/000378 data/0003/000379 data/0003/000380 data/0003/000381 data/0003/000382 data/0003/000383 data/0003/000384 data/0003/000385 data/0003/000386 data/0003/000387 data/0003/000388 data/0003/000389 data/0003/000390 data/0003/000391 data/0003/000392 data/0003/000393 data/0003/000394 data/0003/000395 data/0003/000396 data/0003/000397 data/0003/000398 data/0003/000399 data/0003/000400 data/0003/000401 data/0003/000402 data/0003/000403 data/0003/000404 data/0003/000405 data/0003/000406 data/0003/000407 data/0003/000408 data/0003/000409 data/0003/000410 data/0003/000411 data/0003/000412 data/0003/000413 data/0003/000414 data/0003/000415 data/0003/000416 data/0003/000417 data/0003/000418 data/0003/000419 data/0003/000420 data/0003/000421 data/0003/000422 data/0003/000423 data/0003/000424 data/0003/000425 data/0003/000426 data/0003/000427 data/0003/000428 data/0003/000429 data/0003/000430 data/0003/000431 data/0003/000432 data/0003/000433 data/0003/000434 data/0003/000435 data/0003/000436 data/0003/000437 data/0003/000438 data/0003/000439 data/0003/000440 data/0003/000441 data/0003/000442 data/0003/000443 data/0003/000444 data/0003/000445 data/0003/000446 data/0003/000447 data/0003/000448 data/0003/000449 data/0003/000450 data/0003/000451 data/0003/000452 data/0003/000453 data/0003/000454 data/0003/000455 data/0003/000456 data/0003/000457 data/0003/000458 data/0003/000459 data/0003/000460 data/0003/000461 data/0003/000462 data/0003/000463 data/0003/000464 data/0003/000465 data/0003/000466 data/0003/000467 data/0003/000468 data/0003/000469 data/0003/000470 data/0003/000471 data/0003/000472 data/0003/000473 data/0003/000474 data/0003/000475 data/0003/000476 data/0003/000477 data/0003/000478 data/0003/000479 data/0003/000480 data/0003/000481 data/0003/000482 data/0003/000483 data/0003/000484 data/0003/000485 data/0003/000486 data/0003/000487 data/0003/000488 data/0003/000489 data/0003/000490 data/0003/000491 data/0003/000492 data/0003/000493 data/0003/000494 data/0003/000495 data/0003/000496 data/0003/000497 data/0003/000498 data/0003/000499 data/0003/000500 data/0003/000501 data/0003/000502 data/0003/000503 data/0003/000504 data/0003/000505 data/0003/000506 data/0003/000507 data/0003/000508 data/0003/000509 data/0003/000510 data/0003/000511 data/0003/000512 data/0003/000513 data/0003/000514 data/0003/000515 data/0003/000516 data/0003/000517 data/0003/000518 data/0003/000519 data/0003/000520 data/0003/000521 data/0003/000522 data/0003/000523 data/0003/000524 data/0003/000525 data/0003/000526 data/0003/000527 data/0003/000528 data/0003/000529 data/0003/000530 data/0003/000531 data/0003/000532 data/0003/000533 data/0003/000534 data/0003/000535 data/0003/000536 data/0003/000537 data/0003/000538 data/0003/000539 data/0003/000540 data/0003/000541 data/0003/000542 data/0003/000543 data/0003/000544 data/0003/000545 data/0003/000546 data/0003/000547 data/0003/000548 data/0003/000549 data/0003/000550 data/0003/000551 data/0003/000552 data/0003/000553 data/0003/000554 data/0003/000555 data/0003/000556 data/0003/000557 data/0003/000558 data/0003/000559 data/0003/000560 data/0003/000561 data/0003/000562 data/0003/000563 data/0003/000564 data/0003/000565 data/0003/000566 data/0003/000567 data/0003/000568 data/0003/000569 data/0003/000570 data/0003/000571 data/0003/000572 data/0003/000573 data/0003/000574 data/0003/000575 data/0003/000576 data/0003/000577 data/0003/000578 data/0003/000579 data/0003/000580 data/0003/000581 data/0003/000582 data/0003/000583 data/0003/000584 data/0003/000585 data/0003/000586 data/0003/000587 data/0003/000588 data/0003/000589 data/0003/000590 data/0003/000591 data/0003/000592 data/0003/000593 data/0003/000594 data/0003/000595 data/0003/000596 data/0003/000597 data/0003/000598 data/0003/000599 data/0003/000600 data/0003/000601 data/0003/000602 data/0003/000603 data/0003/000604 data/0003/000605 data/0003/000606 data/0003/000607 data/0003/000608 data/0003/000609 data/0003/000610 data/0003/000611 data/0003/000612 data/0003/000613 data/0003/000614 data/0003/000615 data/0003/000616 data/0003/000617 data/0003/000618 data/0003/000619 data/0003/000620 data/0003/000621 data/0003/000622 data/0003/000623 data/0003/000624 data/0003/000625 data/0003/000626 data/0003/000627 data/0003/000628 data/0003/000629 data/0003/000630 data/0003/000631 data/0003/000632 data/0003/000633 data/0003/000634 data/0003/000635 data/0003/000636 data/0003/000637 data/0003/000638 data/0003/000639 data/0003/000640 data/0003/000641 data/0003/000642 data/0003/000643 data/0003/000644 data/0003/000645 data/0003/000646 data/0003/000647 data/0003/000648 data/0003/000649 data/0003/000650 data/0003/000651 data/0003/000652 data/0003/000653 data/0003/000654 data/0003/000655 data/0003/000656 data/0003/000657 data/0003/000658 data/0003/000659 data/0003/000660 data/0003/000661 data/0003/000662 data/0003/000663 data/0003/000664 data/0003/000665 data/0003/000666 data/0003/000667 data/0003/000668 data/0003/000669 data/0003/000670 data/0003/000671 data/0003/000672 data/0003/000673 data/0003/000674 data/0003/000675 data/0003/000676 data/0003/000677 data/0003/000678 data/0003/000679 data/0003/000680 data/0003/000681 data/0003/000682 data/0003/000683 data/0003/000684 data/0003/000685 data/0003/000686 data/0003/000687 data/0003/000688 data/0003/000689 data/0003/000690 data/0003/000691 data/0003/000692 data/0003/000693 data/0003/000694 data/0003/000695 data/0003/000696 data/0003/000697 data/0003/000698 data/0003/000699 data/0003/000700 data/0003/000701 data/0003/000702 data/0003/000703 data/0003/000704 data/0003/000705 data/0003/000706 data/0003/000707 data/0003/000708 data/0003/000709 data/0003/000710 data/0003/000711 data/0003/000712 data/0003/000713 data/0003/000714 data/0003/000715 data/0003/000716 data/0003/000717 data/0003/000718 data/0003/000719 data/0003/000720 data/0003/000721 data/0003/000722 data/0003/000723 data/0003/000724 data/0003/000725 data/0003/000726 data/0003/000727 data/0003/000728 data/0003/000729 data/0003/000730 data/0003/000731 data/0003/000732 data/0003/000733 data/0003/000734 data/0003/000735 data/0003/000736 data/0003/000737 data/0003/000738 data/0003/000739 data/0003/000740 data/0003/000741 data/0003/000742 data/0003/000743 data/0003/000744 data/0003/000745 data/0003/000746 data/0003/000747 data/0003/000748 data/0003/000749 data/0003/000750 data/0003/000751 data/0003/000752 data/0003/000753 data/0003/000754 data/0003/000755 data/0003/000756 data/0003/000757 data/0003/000758 data/0003/000759 data/0003/000760 data/0003/000761 data/0003/000762 data/0003/000763 data/0003/000764 data/0003/000765 data/0003/000766 data/0003/000767 data/0003/000768 data/0003/000769 data/0003/000770 data/0003/000771 data/0003/000772 data/0003/000773 data/0003/000774 data/0003/000775 data/0003/000776 data/0003/000777 data/0003/000778 data/0003/000779 data/0003/000780 data/0003/000781 data/0003/000782 data/0003/000783 data/0003/000784 data/0003/000785 data/0003/000786 data/0003/000787 data/0003/000788 data/0003/000789 data/0003/000790 data/0003/000791 data/0003/000792 data/0003/000793 data/0003/000794 data/0003/000795 data/0003/000796 data/0003/000797 data/0003/000798 data/0003/000799 data/0003/000800 data/0003/000801 data/0003/000802 data/0003/000803 data/0003/000804 data/0003/000805 data/0003/000806 data/0003/000807 data/0003/000808 data/0003/000809 data/0003/000810 data/0003/000811 data/0003/000812 data/0003/000813 data/0003/000814 data/0003/000815 data/0003/000816 data/0003/000817 data/0003/000818 data/0003/000819 data/0003/000820 data/0003/000821 data/0003/000822 data/0003/000823 data/0003/000824 data/0003/000825 data/0003/000826 data/0003/000827 data/0003/000828 data/0003/000829 data/0003/000830 data/0003/000831 data/0003/000832 data/0003/000833 data/0003/000834 data/0003/000835 data/0003/000836 data/0003/000837 data/0003/000838 data/0003/000839 data/0003/000840 data/0003/000841 data/0003/000842 data/0003/000843 data/0003/000844 data/0003/000845 data/0003/000846 data/0003/000847 data/0003/000848 data/0003/000849 data/0003/000850 data/0003/000851 data/0003/000852 data/0003/000853 data/0003/000854 data/0003/000855 data/0003/000856 data/0003/000857 data/0003/000858 data/0003/000859 data/0003/000860 data/0003/000861 data/0003/000862 data/0003/000863 data/0003/000864 data/0003/000865 data/0003/000866 data/0003/000867 data/0003/000868 data/0003/000869 data/0003/000870 data/0003/000871 data/0003/000872 data/0003/000873 data/0003/000874 data/0003/000875 data/0003/000876 data/0003/000877 data/0003/000878 data/0003/000879 data/0003/000880 data/0003/000881 data/0003/000882 data/0003/000883 data/0003/000884 data/0003/000885 data/0003/000886 data/0003/000887 data/0003/000888 data/0003/000889 data/0003/000890 data/0003/000891 data/0003/000892 data/0003/000893 data/0003/000894 data/0003/000895 data/0003/000896 data/0003/000897 data/0003/000898 data/0003/000899 data/0003/000900 data/0003/000901 data/0003/000902 data/0003/000903 data/0003/000904 data/0003/000905 data/0003/000906 data/0003/000907 data/0003/000908 data/0003/000909 data/0003/000910 data/0003/000911 data/0003/000912 data/0003/000913 data/0003/000914 data/0003/000915 data/0003/000916 data/0003/000917 data/0003/000918 data/0003/000919 data/0003/000920 data/0003/000921 data/0003/000922 data/0003/000923 data/0003/000924 data/0003/000925 data/0003/000926 data/0003/000927 data/0003/000928 data/0003/000929 data/0003/000930 data/0003/000931 data/0003/000932 data/0003/000933 data/0003/000934 data/0003/000935 data/0003/000936 data/0003/000937 data/0003/000938 data/0003/000939 data/0003/000940 data/0003/000941 data/0003/000942 data/0003/000943 data/0003/000944 data/0003/000945 data/0003/000946 data/0003/000947 data/0003/000948 data/0003/000949 data/0003/000950 data/0003/000951 data/0003/000952 data/0003/000953 data/0003/000954 data/0003/000955 data/0003/000956 data/0003/000957 data/0003/000958 data/0003/000959 data/0003/000960 data/0003/000961 data/0003/000962 data/0003/000963 data/0003/000964 data/0003/000965 data/0003/000966 data/0003/000967 data/0003/000968 data/0003/000969 data/0003/000970 data/0003/000971 data/0003/000972 data/0003/000973 data/0003/000974 data/0003/000975 data/0003/000976 data/0003/000977 data/0003/000978 data/0003/000979 data/0003/000980 data/0003/000981 data/0003/000982 data/0003/000983 data/0003/000984 data/0003/000985 data/0003/000986 data/0003/000987 data/0003/000988 data/0003/000989 data/0003/000990 data/0003/000991 data/0003/000992 data/0003/000993 data/0003/000994 data/0003/000995 data/0003/000996 data/0003/000997 data/0003/000998 data/0003/000999 data/0003/001000 data/0003/001001 data/0003/001002 data/0003/001003 data/0003/001004 data/0003/001005 data/0003/001006 data/0003/001007 data/0003/001008 data/0003/001009 data/0003/001010 data/0003/001011 data/0003/001012 data/0003/001013 data/0003/001014 data/0003/001015 data/0003/001016 data/0003/001017 data/0003/001018 data/0003/001019 data/0003/001020 data/0003/001021 data/0003/001022 data/0003/001023 data/0003/001024 data/0003/001025 data/0003/001026 data/0003/001027 data/0003/001028 data/0003/001029 data/0003/001030 data/0003/001031 data/0003/001032 data/0003/001033 data/0003/001034 data/0003/001035 data/0003/001036 data/0003/001037 data/0003/001038 data/0003/001039 data/0003/001040 data/0003/001041 data/0003/001042 data/0003/001043 data/0003/001044 data/0003/001045 data/0003/001046 data/0003/001047 data/0003/001048 data/0003/001049 data/0003/001050 data/0003/001051 data/0003/001052 data/0003/001053 data/0003/001054 data/0003/001055 data/0003/001056 data/0003/001057 data/0003/001058 data/0003/001059 data/0003/001060 data/0003/001061 data/0003/001062 data/0003/001063 data/0003/001064 data/0003/001065 data/0003/001066 data/0003/001067 data/0003/001068 data/0003/001069 data/0003/001070 data/0003/001071 data/0003/001072 data/0003/001073 data/0003/001074 data/0003/001075 data/0003/001076 data/0003/001077 data/0003/001078 data/0003/001079 data/0003/001080 data/0003/001081 data/0003/001082 data/0003/001083 data/0003/001084 data/0003/001085 data/0003/001086 data/0003/001087 data/0003/001088 data/0003/001089 data/0003/001090 data/0003/001091 data/0003/001092 data/0003/001093 data/0003/001094 data/0003/001095 data/0003/001096 data/0003/001097 data/0003/001098 data/0003/001099 data/0003/001100 data/0003/001101 data/0003/001102 data/0003/001103 data/0003/001104 data/0003/001105 data/0003/001106 data/0003/001107 data/0003/001108 data/0003/001109 data/0003/001110 data/0003/001111 data/0003/001112 data/0003/001113 data/0003/001114 data/0003/001115 data/0003/001116 data/0003/001117 data/0003/001118 data/0003/001119 data/0003/001120 data/0003/001121 data/0003/001122 data/0003/001123 data/0003/001124 data/0003/001125 data/0003/001126 data/0003/001127 data/0003/001128 data/0003/001129 data/0003/001130 data/0003/001131 data/0003/001132 data/0003/001133 data/0003/001134 data/0003/001135 data/0003/001136 data/0003/001137 data/0003/001138 data/0003/001139 data/0003/001140 data/0003/001141 data/0003/001142 data/0003/001143 data/0003/001144 data/0003/001145 data/0003/001146 data/0003/001147 data/0003/001148 data/0003/001149 data/0003/001150 data/0003/001151 data/0003/001152 data/0003/001153 data/0003/001154 data/0003/001155 data/0003/001156 data/0003/001157 data/0003/001158 data/0003/001159 data/0003/001160 data/0003/001161 data/0003/001162 data/0003/001163 data/0003/001164 data/0003/001165 data/0003/001166 data/0003/001167 data/0003/001168 data/0003/001169 data/0003/001170 data/0003/001171 data/0003/001172 data/0003/001173 data/0003/001174 data/0003/001175 data/0003/001176 data/0003/001177 data/0003/001178 data/0003/001179 data/0003/001180 data/0003/001181 data/0003/001182 data/0003/001183 data/0003/001184 data/0003/001185 data/0003/001186 data/0003/001187 data/0003/001188 data/0003/001189 data/0003/001190 data/0003/001191 data/0003/001192 data/0003/001193 data/0003/001194 data/0003/001195 data/0003/001196 data/0003/001197 data/0003/001198 data/0003/001199 data/0003/001200 data/0003/001201 data/0003/001202 data/0003/001203 data/0003/001204 data/0003/001205 data/0003/001206 data/0003/001207 data/0003/001208 data/0003/001209 data/0003/001210 data/0003/001211 data/0003/001212 data/0003/001213 data/0003/001214 data/0003/001215 data/0003/001216 data/0003/001217 data/0003/001218 data/0003/001219 data/0003/001220 data/0003/001221 data/0003/001222 data/0003/001223 data/0003/001224 data/0003/001225 data/0003/001226 data/0003/001227 data/0003/001228 data/0003/001229 data/0003/001230 data/0003/001231 data/0003/001232 data/0003/001233 data/0003/001234 data/0003/001235 data/0003/001236 data/0003/001237 data/0003/001238 data/0003/001239 data/0003/001240 data/0003/001241 data/0003/001242 data/0003/001243 data/0003/001244 data/0003/001245 data/0003/001246 data/0003/001247 data/0003/001248 data/0003/001249 data/0003/001250 data/0003/001251 data/0003/001252 data/0003/001253 data/0003/001254 data/0003/001255 data/0003/001256 data/0003/001257 data/0003/001258 data/0003/001259 data/0003/001260 data/0003/001261 data/0003/001262 data/0003/001263 data/0003/001264 data/0003/001265 data/0003/001266 data/0003/001267 data/0003/001268 data/0003/001269 data/0003/001270 data/0003/001271 data/0003/001272 data/0003/001273 data/0003/001274 data/0003/001275 data/0003/001276 data/0003/001277 data/0003/001278 data/0003/001279 data/0003/001280 data/0003/001281 data/0003/001282 data/0003/001283 data/0003/001284 data/0003/001285 data/0003/001286 data/0003/001287 data/0003/001288 data/0003/001289 data/0003/001290 data/0003/001291 data/0003/001292 data/0003/001293 data/0003/001294 data/0003/001295 data/0003/001296 data/0003/001297 data/0003/001298 data/0003/001299 data/0003/001300 data/0003/001301 data/0003/001302 data/0003/001303 data/0003/001304 data/0003/001305 data/0003/001306 data/0003/001307 data/0003/001308 data/0003/001309 data/0003/001310 data/0003/001311 data/0003/001312 data/0003/001313 data/0003/001314 data/0003/001315 data/0003/001316 data/0003/001317 data/0003/001318 data/0003/001319 data/0003/001320 data/0003/001321 data/0003/001322 data/0003/001323 data/0003/001324 data/0003/001325 data/0003/001326 data/0003/001327 data/0003/001328 data/0003/001329 data/0003/001330 data/0003/001331 data/0003/001332 data/0003/001333 data/0003/001334 data/0003/001335 data/0003/001336 data/0003/001337 data/0003/001338 data/0003/001339 data/0003/001340 data/0003/001341 data/0003/001342 data/0003/001343 data/0003/001344 data/0003/001345 data/0003/001346 data/0003/001347 data/0003/001348 data/0003/001349 data/0003/001350 data/0003/001351 data/0003/001352 data/0003/001353 data/0003/001354 data/0003/001355 data/0003/001356 data/0003/001357 data/0003/001358 data/0003/001359 data/0003/001360 data/0003/001361 data/0003/001362 data/0003/001363 data/0003/001364 data/0003/001365 data/0003/001366 data/0003/001367 data/0003/001368 data/0003/001369 data/0003/001370 data/0003/001371 data/0003/001372 data/0003/001373 data/0003/001374 data/0003/001375 data/0003/001376 data/0003/001377 data/0003/001378 data/0003/001379 data/0003/001380 data/0003/001381 data/0003/001382 data/0003/001383 data/0003/001384 data/0003/001385 data/0003/001386 data/0003/001387 data/0003/001388 data/0003/001389 data/0003/001390 data/0003/001391 data/0003/001392 data/0003/001393 data/0003/001394 data/0003/001395 data/0003/001396 data/0003/001397 data/0003/001398 data/0003/001399 data/0003/001400 data/0003/001401 data/0003/001402 data/0003/001403 data/0003/001404 data/0003/001405 data/0003/001406 data/0003/001407 data/0003/001408 data/0003/001409 data/0003/001410 data/0003/001411 data/0003/001412 data/0003/001413 data/0003/001414 data/0003/001415 data/0003/001416 data/0003/001417 data/0003/001418 data/0003/001419 data/0003/001420 data/0003/001421 data/0003/001422 data/0003/001423 data/0003/001424 data/0003/001425 data/0003/001426 data/0003/001427 data/0003/001428 data/0003/001429 data/0003/001430 data/0003/001431 data/0003/001432 data/0003/001433 data/0003/001434 data/0003/001435 data/0003/001436 data/0003/001437 data/0003/001438 data/0003/001439 data/0003/001440 data/0003/001441 data/0003/001442 data/0003/001443 data/0003/001444 data/0003/001445 data/0003/001446 data/0003/001447 data/0003/001448 data/0003/001449 data/0003/001450 data/0003/001451 data/0003/001452 data/0003/001453 data/0003/001454 data/0003/001455 data/0003/001456 data/0003/001457 data/0003/001458 data/0003/001459 data/0003/001460 data/0003/001461 data/0003/001462 data/0003/001463 data/0003/001464 data/0003/001465 data/0003/001466 data/0003/001467 data/0003/001468 data/0003/001469 data/0003/001470 data/0003/001471 data/0003/001472 data/0003/001473 data/0003/001474 data/0003/001475 data/0003/001476 data/0003/001477 data/0003/001478 data/0003/001479 data/0003/001480 data/0003/001481 data/0003/001482 data/0003/001483 data/0003/001484 data/0003/001485 data/0003/001486 data/0003/001487 data/0003/001488 data/0003/001489 data/0003/001490 data/0003/001491 data/0003/001492 data/0003/001493 data/0003/001494 data/0003/001495 data/0003/001496 data/0003/001497 data/0003/001498 data/0003/001499 data/0003/001500 data/0003/001501 data/0003/001502 data/0003/001503 data/0003/001504 data/0003/001505 data/0003/001506 data/0003/001507 data/0003/001508 data/0003/001509 data/0003/001510 data/0003/001511 data/0003/001512 data/0003/001513 data/0003/001514 data/0003/001515 data/0003/001516 data/0003/001517 data/0003/001518 data/0003/001519 data/0003/001520 data/0003/001521 data/0003/001522 data/0003/001523 data/0003/001524 data/0003/001525 data/0003/001526 data/0003/001527 data/0003/001528 data/0003/001529 data/0003/001530 data/0003/001531 data/0003/001532 data/0003/001533 data/0003/001534 data/0003/001535 data/0003/001536 data/0003/001537 data/0003/001538 data/0003/001539 data/0003/001540 data/0003/001541 data/0003/001542 data/0003/001543 data/0003/001544 data/0003/001545 data/0003/001546 data/0003/001547 data/0003/001548 data/0003/001549 data/0003/001550 data/0003/001551 data/0003/001552 data/0003/001553 data/0003/001554 data/0003/001555 data/0003/001556 data/0003/001557 data/0003/001558 data/0003/001559 data/0003/001560 data/0003/001561 data/0003/001562 data/0003/001563 data/0003/001564 data/0003/001565 data/0003/001566 data/0003/001567 data/0003/001568 data/0003/001569 data/0003/001570 data/0003/001571 data/0003/001572 data/0003/001573 data/0003/001574 data/0003/001575 data/0003/001576 data/0003/001577 data/0003/001578 data/0003/001579 data/0003/001580 data/0003/001581 data/0003/001582 data/0003/001583 data/0003/001584 data/0003/001585 data/0003/001586 data/0003/001587 data/0003/001588 data/0003/001589 data/0003/001590 data/0003/001591 data/0003/001592 data/0003/001593 data/0003/001594 data/0003/001595 data/0003/001596 data/0003/001597 data/0003/001598 data/0003/001599 data/0003/001600 data/0003/001601 data/0003/001602 data/0003/001603 data/0003/001604 data/0003/001605 data/0003/001606 data/0003/001607 data/0003/001608 data/0003/001609 data/0003/001610 data/0003/001611 data/0003/001612 data/0003/001613 data/0003/001614 data/0003/001615 data/0003/001616 data/0003/001617 data/0003/001618 data/0003/001619 data/0003/001620 data/0003/001621 data/0003/001622 data/0003/001623 data/0003/001624 data/0003/001625 data/0003/001626 data/0003/001627 data/0011/000001 data/0011/000002 data/0011/000003 data/0011/000004 data/0011/000005 data/0011/000006 data/0011/000007 data/0011/000008 data/0011/000009 data/0011/000010 data/0011/000011 data/0011/000012 data/0011/000013 data/0011/000014 data/0011/000015 data/0011/000016 data/0011/000017 data/0011/000018 data/0011/000019 data/0011/000020 data/0011/000021 data/0011/000022 data/0011/000023 data/0011/000024 data/0011/000025 data/0011/000026 data/0011/000027 data/0011/000028 data/0011/000029 data/0011/000030 data/0011/000031 data/0011/000032 data/0011/000033 data/0011/000034 data/0011/000035 data/0011/000036 data/0011/000037 data/0011/000038 data/0011/000039 data/0011/000040 data/0011/000041 data/0011/000042 data/0011/000043 data/0011/000044 data/0011/000045 data/0011/000046 data/0011/000047 data/0011/000048 data/0011/000049 data/0011/000050 data/0011/000051 data/0011/000052 data/0011/000053 data/0011/000054 data/0011/000055 data/0011/000056 data/0011/000057 data/0011/000058 data/0011/000059 data/0011/000060 data/0011/000061 data/0011/000062 data/0011/000063 data/0011/000064 data/0011/000065 data/0011/000066 data/0011/000067 data/0011/000068 data/0011/000069 data/0011/000070 data/0011/000071 data/0011/000072 data/0011/000073 data/0011/000074 data/0011/000075 data/0011/000076 data/0011/000077 data/0011/000078 data/0011/000079 data/0011/000080 data/0011/000081 data/0011/000082 data/0011/000083 data/0011/000084 data/0011/000085 data/0011/000086 data/0011/000087 data/0011/000088 data/0011/000089 data/0011/000090 data/0011/000091 data/0011/000092 data/0011/000093 data/0011/000094 data/0011/000095 data/0011/000096 data/0011/000097 data/0011/000098 data/0011/000099 data/0011/000100 data/0011/000101 data/0011/000102 data/0011/000103 data/0011/000104 data/0011/000105 data/0011/000106 data/0011/000107 data/0011/000108 data/0011/000109 data/0011/000110 data/0011/000111 data/0011/000112 data/0011/000113 data/0011/000114 data/0011/000115 data/0011/000116 data/0011/000117 data/0011/000118 data/0011/000119 data/0011/000120 data/0011/000121 data/0011/000122 data/0011/000123 data/0011/000124 data/0011/000125 data/0011/000126 data/0011/000127 data/0011/000128 data/0011/000129 data/0011/000130 data/0011/000131 data/0011/000132 data/0011/000133 data/0011/000134 data/0011/000135 data/0011/000136 data/0011/000137 data/0011/000138 data/0011/000139 data/0011/000140 data/0011/000141 data/0011/000142 data/0011/000143 data/0011/000144 data/0011/000145 data/0011/000146 data/0011/000147 data/0011/000148 data/0011/000149 data/0011/000150 data/0011/000151 data/0011/000152 data/0011/000153 data/0011/000154 data/0011/000155 data/0011/000156 data/0011/000157 data/0011/000158 data/0011/000159 data/0011/000160 data/0011/000161 data/0011/000162 data/0011/000163 data/0011/000164 data/0011/000165 data/0011/000166 data/0011/000167 data/0011/000168 data/0011/000169 data/0011/000170 data/0011/000171 data/0011/000172 data/0011/000173 data/0011/000174 data/0011/000175 data/0011/000176 data/0011/000177 data/0011/000178 data/0011/000179 data/0011/000180 data/0011/000181 data/0011/000182 data/0011/000183 data/0011/000184 data/0011/000185 data/0011/000186 data/0011/000187 data/0011/000188 data/0011/000189 data/0011/000190 data/0011/000191 data/0011/000192 data/0011/000193 data/0011/000194 data/0011/000195 data/0011/000196 data/0011/000197 data/0011/000198 data/0011/000199 data/0011/000200 data/0011/000201 data/0011/000202 data/0011/000203 data/0011/000204 data/0011/000205 data/0011/000206 data/0011/000207 data/0011/000208 data/0011/000209 data/0011/000210 data/0011/000211 data/0011/000212 data/0011/000213 data/0011/000214 data/0011/000215 data/0011/000216 data/0011/000217 data/0011/000218 data/0011/000219 data/0011/000220 data/0011/000221 data/0011/000222 data/0011/000223 data/0011/000224 data/0011/000225 data/0011/000226 data/0011/000227 data/0011/000228 data/0011/000229 data/0011/000230 data/0011/000231 data/0011/000232 data/0011/000233 data/0011/000234 data/0011/000235 data/0011/000236 data/0011/000237 data/0011/000238 data/0011/000239 data/0011/000240 data/0011/000241 data/0011/000242 data/0011/000243 data/0011/000244 data/0011/000245 data/0011/000246 data/0011/000247 data/0011/000248 data/0011/000249 data/0011/000250 data/0011/000251 data/0011/000252 data/0011/000253 data/0011/000254 data/0011/000255 data/0011/000256 data/0011/000257 data/0011/000258 data/0011/000259 data/0011/000260 data/0011/000261 data/0011/000262 data/0011/000263 data/0011/000264 data/0011/000265 data/0011/000266 data/0011/000267 data/0011/000268 data/0011/000269 data/0011/000270 data/0011/000271 data/0011/000272 data/0011/000273 data/0011/000274 data/0011/000275 data/0011/000276 data/0011/000277 data/0011/000278 data/0011/000279 data/0011/000280 data/0011/000281 data/0011/000282 data/0011/000283 data/0011/000284 data/0011/000285 data/0011/000286 data/0011/000287 data/0011/000288 data/0011/000289 data/0011/000290 data/0011/000291 data/0011/000292 data/0011/000293 data/0011/000294 data/0011/000295 data/0011/000296 data/0011/000297 data/0011/000298 data/0011/000299 data/0011/000300 data/0011/000301 data/0011/000302 data/0011/000303 data/0011/000304 data/0011/000305 data/0011/000306 data/0011/000307 data/0011/000308 data/0011/000309 data/0011/000310 data/0011/000311 data/0011/000312 data/0011/000313 data/0011/000314 data/0011/000315 data/0011/000316 data/0011/000317 data/0011/000318 data/0011/000319 data/0011/000320 data/0011/000321 data/0011/000322 data/0011/000323 data/0011/000324 data/0011/000325 data/0011/000326 data/0011/000327 data/0011/000328 data/0011/000329 data/0011/000330 data/0011/000331 data/0011/000332 data/0011/000333 data/0011/000334 data/0011/000335 data/0011/000336 data/0011/000337 data/0011/000338 data/0011/000339 data/0011/000340 data/0011/000341 data/0011/000342 data/0011/000343 data/0011/000344 data/0011/000345 data/0011/000346 data/0011/000347 data/0011/000348 data/0011/000349 data/0011/000350 data/0011/000351 data/0011/000352 data/0011/000353 data/0011/000354 data/0011/000355 data/0011/000356 data/0011/000357 data/0011/000358 data/0011/000359 data/0011/000360 data/0011/000361 data/0011/000362 data/0011/000363 data/0011/000364 data/0011/000365 data/0011/000366 data/0011/000367 data/0011/000368 data/0011/000369 data/0011/000370 data/0011/000371 data/0011/000372 data/0011/000373 data/0011/000374 data/0011/000375 data/0011/000376 data/0011/000377 data/0011/000378 data/0011/000379 data/0011/000380 data/0011/000381 data/0011/000382 data/0011/000383 data/0011/000384 data/0011/000385 data/0011/000386 data/0011/000387 data/0011/000388 data/0011/000389 data/0011/000390 data/0011/000391 data/0011/000392 data/0011/000393 data/0011/000394 data/0011/000395 data/0011/000396 data/0011/000397 data/0011/000398 data/0011/000399 data/0011/000400 data/0011/000401 data/0011/000402 data/0011/000403 data/0011/000404 data/0011/000405 data/0011/000406 data/0011/000407 data/0011/000408 data/0011/000409 data/0011/000410 data/0011/000411 data/0011/000412 data/0011/000413 data/0011/000414 data/0011/000415 data/0011/000416 data/0011/000417 data/0011/000418 data/0011/000419 data/0011/000420 data/0011/000421 data/0011/000422 data/0011/000423 data/0011/000424 data/0011/000425 data/0011/000426 data/0011/000427 data/0011/000428 data/0011/000429 data/0011/000430 data/0011/000431 data/0011/000432 data/0011/000433 data/0011/000434 data/0011/000435 data/0011/000436 data/0011/000437 data/0011/000438 data/0011/000439 data/0011/000440 data/0011/000441 data/0011/000442 data/0011/000443 data/0011/000444 data/0011/000445 data/0011/000446 data/0011/000447 data/0011/000448 data/0011/000449 data/0011/000450 data/0011/000451 data/0011/000452 data/0011/000453 data/0011/000454 data/0011/000455 data/0011/000456 data/0011/000457 data/0011/000458 data/0011/000459 data/0011/000460 data/0011/000461 data/0011/000462 data/0011/000463 data/0011/000464 data/0011/000465 data/0011/000466 data/0011/000467 data/0011/000468 data/0011/000469 data/0011/000470 data/0011/000471 data/0011/000472 data/0011/000473 data/0011/000474 data/0011/000475 data/0011/000476 data/0011/000477 data/0011/000478 data/0011/000479 data/0011/000480 data/0011/000481 data/0011/000482 data/0011/000483 data/0011/000484 data/0011/000485 data/0011/000486 data/0011/000487 data/0011/000488 data/0011/000489 data/0011/000490 data/0011/000491 data/0011/000492 data/0011/000493 data/0011/000494 data/0011/000495 data/0011/000496 data/0011/000497 data/0011/000498 data/0011/000499 data/0011/000500 data/0011/000501 data/0011/000502 data/0011/000503 data/0011/000504 data/0011/000505 data/0011/000506 data/0011/000507 data/0011/000508 data/0011/000509 data/0011/000510 data/0011/000511 data/0011/000512 data/0011/000513 data/0011/000514 data/0011/000515 data/0011/000516 data/0011/000517 data/0011/000518 data/0011/000519 data/0011/000520 data/0011/000521 data/0011/000522 data/0011/000523 data/0011/000524 data/0011/000525 data/0011/000526 data/0011/000527 data/0011/000528 data/0011/000529 data/0011/000530 data/0011/000531 data/0011/000532 data/0011/000533 data/0011/000534 data/0011/000535 data/0011/000536 data/0011/000537 data/0011/000538 data/0011/000539 data/0011/000540 data/0011/000541 data/0011/000542 data/0011/000543 data/0011/000544 data/0011/000545 data/0011/000546 data/0011/000547 data/0011/000548 data/0011/000549 data/0011/000550 data/0011/000551 data/0011/000552 data/0011/000553 data/0011/000554 data/0011/000555 data/0011/000556 data/0011/000557 data/0011/000558 data/0011/000559 data/0011/000560 data/0011/000561 data/0011/000562 data/0011/000563 data/0011/000564 data/0011/000565 data/0011/000566 data/0011/000567 data/0011/000568 data/0011/000569 data/0011/000570 data/0011/000571 data/0011/000572 data/0011/000573 data/0011/000574 data/0011/000575 data/0011/000576 data/0011/000577 data/0011/000578 data/0011/000579 data/0011/000580 data/0011/000581 data/0011/000582 data/0011/000583 data/0011/000584 data/0011/000585 data/0011/000586 data/0011/000587 data/0011/000588 data/0011/000589 data/0011/000590 data/0011/000591 data/0011/000592 data/0011/000593 data/0011/000594 data/0011/000595 data/0011/000596 data/0011/000597 data/0011/000598 data/0011/000599 data/0011/000600 data/0011/000601 data/0011/000602 data/0011/000603 data/0011/000604 data/0011/000605 data/0011/000606 data/0011/000607 data/0011/000608 data/0011/000609 data/0011/000610 data/0011/000611 data/0011/000612 data/0011/000613 data/0011/000614 data/0011/000615 data/0011/000616 data/0011/000617 data/0011/000618 data/0011/000619 data/0011/000620 data/0011/000621 data/0011/000622 data/0011/000623 data/0011/000624 data/0011/000625 data/0011/000626 data/0011/000627 data/0011/000628 data/0011/000629 data/0011/000630 data/0011/000631 data/0011/000632 data/0011/000633 data/0011/000634 data/0011/000635 data/0011/000636 data/0011/000637 data/0011/000638 data/0011/000639 data/0011/000640 data/0011/000641 data/0011/000642 data/0011/000643 data/0011/000644 data/0011/000645 data/0011/000646 data/0011/000647 data/0011/000648 data/0011/000649 data/0011/000650 data/0011/000651 data/0011/000652 data/0011/000653 data/0011/000654 data/0011/000655 data/0011/000656 data/0011/000657 data/0011/000658 data/0011/000659 data/0011/000660 data/0011/000661 data/0011/000662 data/0011/000663 data/0011/000664 data/0011/000665 data/0011/000666 data/0011/000667 data/0011/000668 data/0011/000669 data/0011/000670 data/0011/000671 data/0011/000672 data/0011/000673 data/0011/000674 data/0011/000675 data/0011/000676 data/0011/000677 data/0011/000678 data/0011/000679 data/0011/000680 data/0011/000681 data/0011/000682 data/0011/000683 data/0011/000684 data/0011/000685 data/0011/000686 data/0011/000687 data/0011/000688 data/0011/000689 data/0011/000690 data/0011/000691 data/0011/000692 data/0011/000693 data/0011/000694 data/0011/000695 data/0011/000696 data/0011/000697 data/0011/000698 data/0011/000699 data/0011/000700 data/0011/000701 data/0011/000702 data/0011/000703 data/0011/000704 data/0011/000705 data/0011/000706 data/0011/000707 data/0011/000708 data/0011/000709 data/0011/000710 data/0011/000711 data/0011/000712 data/0011/000713 data/0011/000714 data/0011/000715 data/0011/000716 data/0011/000717 data/0011/000718 data/0011/000719 data/0011/000720 data/0011/000721 data/0011/000722 data/0011/000723 data/0011/000724 data/0011/000725 data/0011/000726 data/0011/000727 data/0011/000728 data/0011/000729 data/0011/000730 data/0011/000731 data/0011/000732 data/0011/000733 data/0011/000734 data/0011/000735 data/0011/000736 data/0011/000737 data/0011/000738 data/0011/000739 data/0011/000740 data/0011/000741 data/0011/000742 data/0011/000743 data/0011/000744 data/0011/000745 data/0011/000746 data/0011/000747 data/0011/000748 data/0011/000749 data/0011/000750 data/0011/000751 data/0011/000752 data/0011/000753 data/0011/000754 data/0011/000755 data/0011/000756 data/0011/000757 data/0011/000758 data/0011/000759 data/0011/000760 data/0011/000761 data/0011/000762 data/0011/000763 data/0011/000764 data/0011/000765 data/0011/000766 data/0011/000767 data/0011/000768 data/0011/000769 data/0011/000770 data/0011/000771 data/0011/000772 data/0011/000773 data/0011/000774 data/0011/000775 data/0011/000776 data/0011/000777 data/0011/000778 data/0011/000779 data/0011/000780 data/0011/000781 data/0011/000782 data/0011/000783 data/0011/000784 data/0011/000785 data/0011/000786 data/0011/000787 data/0011/000788 data/0011/000789 data/0011/000790 data/0011/000791 data/0011/000792 data/0011/000793 data/0011/000794 data/0011/000795 data/0011/000796 data/0011/000797 data/0011/000798 data/0011/000799 data/0011/000800 data/0011/000801 data/0011/000802 data/0011/000803 data/0011/000804 data/0011/000805 data/0011/000806 data/0011/000807 data/0011/000808 data/0011/000809 data/0011/000810 data/0011/000811 data/0011/000812 data/0011/000813 data/0011/000814 data/0011/000815 data/0011/000816 data/0011/000817 data/0011/000818 data/0011/000819 data/0011/000820 data/0011/000821 data/0011/000822 data/0011/000823 data/0011/000824 data/0011/000825 data/0011/000826 data/0011/000827 data/0011/000828 data/0011/000829 data/0011/000830 data/0011/000831 data/0011/000832 data/0011/000833 data/0011/000834 data/0011/000835 data/0011/000836 data/0011/000837 data/0011/000838 data/0011/000839 data/0011/000840 data/0011/000841 data/0011/000842 data/0011/000843 data/0011/000844 data/0011/000845 data/0011/000846 data/0011/000847 data/0011/000848 data/0017/000001 data/0017/000002 data/0017/000003 data/0017/000004 data/0017/000005 data/0017/000006 data/0017/000007 data/0017/000008 data/0017/000009 data/0017/000010 data/0017/000011 data/0017/000012 data/0017/000013 data/0017/000014 data/0017/000015 data/0017/000016 data/0017/000017 data/0017/000018 data/0017/000019 data/0017/000020 data/0017/000021 data/0017/000022 data/0017/000023 data/0017/000024 data/0017/000025 data/0017/000026 data/0017/000027 data/0017/000028 data/0017/000029 data/0017/000030 data/0017/000031 data/0017/000032 data/0017/000033 data/0017/000034 data/0017/000035 data/0017/000036 data/0017/000037 data/0017/000038 data/0017/000039 data/0017/000040 data/0017/000041 data/0017/000042 data/0017/000043 data/0017/000044 data/0017/000045 data/0017/000046 data/0017/000047 data/0017/000048 data/0017/000049 data/0017/000050 data/0017/000051 data/0017/000052 data/0017/000053 data/0017/000054 data/0017/000055 data/0017/000056 data/0017/000057 data/0017/000058 data/0017/000059 data/0017/000060 data/0017/000061 data/0017/000062 data/0017/000063 data/0017/000064 data/0017/000065 data/0017/000066 data/0017/000067 data/0017/000068 data/0017/000069 data/0017/000070 data/0017/000071 data/0017/000072 data/0017/000073 data/0017/000074 data/0017/000075 data/0017/000076 data/0017/000077 data/0017/000078 data/0017/000079 data/0017/000080 data/0017/000081 data/0017/000082 data/0017/000083 data/0017/000084 data/0017/000085 data/0017/000086 data/0017/000087 data/0017/000088 data/0017/000089 data/0017/000090 data/0017/000091 data/0017/000092 data/0017/000093 data/0017/000094 data/0017/000095 data/0017/000096 data/0017/000097 data/0017/000098 data/0017/000099 data/0017/000100 data/0017/000101 data/0017/000102 data/0017/000103 data/0017/000104 data/0017/000105 data/0017/000106 data/0017/000107 data/0017/000108 data/0017/000109 data/0017/000110 data/0017/000111 data/0017/000112 data/0017/000113 data/0017/000114 data/0017/000115 data/0017/000116 data/0017/000117 data/0017/000118 data/0017/000119 data/0017/000120 data/0017/000121 data/0017/000122 data/0017/000123 data/0017/000124 data/0017/000125 data/0017/000126 data/0017/000127 data/0017/000128 data/0017/000129 data/0017/000130 data/0017/000131 data/0017/000132 data/0017/000133 data/0017/000134 data/0017/000135 data/0017/000136 data/0017/000137 data/0017/000138 data/0017/000139 data/0017/000140 data/0017/000141 data/0017/000142 data/0017/000143 data/0017/000144 data/0017/000145 data/0017/000146 data/0017/000147 data/0017/000148 data/0017/000149 data/0017/000150 data/0017/000151 data/0017/000152 data/0017/000153 data/0017/000154 data/0017/000155 data/0017/000156 data/0017/000157 data/0017/000158 data/0017/000159 data/0017/000160 data/0017/000161 data/0017/000162 data/0017/000163 data/0017/000164 data/0017/000165 data/0017/000166 data/0017/000167 data/0017/000168 data/0017/000169 data/0017/000170 data/0017/000171 data/0017/000172 data/0017/000173 data/0017/000174 data/0017/000175 data/0017/000176 data/0017/000177 data/0017/000178 data/0017/000179 data/0017/000180 data/0017/000181 data/0017/000182 data/0017/000183 data/0017/000184 data/0017/000185 data/0017/000186 data/0017/000187 data/0017/000188 data/0017/000189 data/0017/000190 data/0017/000191 data/0017/000192 data/0017/000193 data/0017/000194 data/0017/000195 data/0017/000196 data/0017/000197 data/0017/000198 data/0017/000199 data/0017/000200 data/0017/000201 data/0017/000202 data/0017/000203 data/0017/000204 data/0017/000205 data/0017/000206 data/0017/000207 data/0017/000208 data/0017/000209 data/0017/000210 data/0017/000211 data/0017/000212 data/0017/000213 data/0017/000214 data/0017/000215 data/0017/000216 data/0017/000217 data/0017/000218 data/0017/000219 data/0017/000220 data/0017/000221 data/0017/000222 data/0017/000223 data/0017/000224 data/0017/000225 data/0017/000226 data/0017/000227 data/0017/000228 data/0017/000229 data/0017/000230 data/0017/000231 data/0017/000232 data/0017/000233 data/0017/000234 data/0017/000235 data/0017/000236 data/0017/000237 data/0017/000238 data/0017/000239 data/0017/000240 data/0017/000241 data/0017/000242 data/0017/000243 data/0017/000244 data/0017/000245 data/0017/000246 data/0017/000247 data/0017/000248 data/0017/000249 data/0017/000250 data/0017/000251 data/0017/000252 data/0017/000253 data/0017/000254 data/0017/000255 data/0017/000256 data/0017/000257 data/0017/000258 data/0017/000259 data/0017/000260 data/0017/000261 data/0017/000262 data/0017/000263 data/0017/000264 data/0017/000265 data/0017/000266 data/0017/000267 data/0017/000268 data/0017/000269 data/0017/000270 data/0017/000271 data/0017/000272 data/0017/000273 data/0017/000274 data/0017/000275 data/0017/000276 data/0017/000277 data/0017/000278 data/0017/000279 data/0017/000280 data/0017/000281 data/0017/000282 data/0017/000283 data/0017/000284 data/0017/000285 data/0017/000286 data/0017/000287 data/0017/000288 data/0017/000289 data/0017/000290 data/0017/000291 data/0017/000292 data/0017/000293 data/0017/000294 data/0017/000295 data/0017/000296 data/0017/000297 data/0017/000298 data/0017/000299 data/0017/000300 data/0017/000301 data/0017/000302 data/0017/000303 data/0017/000304 data/0017/000305 data/0017/000306 data/0017/000307 data/0017/000308 data/0017/000309 data/0017/000310 data/0017/000311 data/0017/000312 data/0017/000313 data/0017/000314 data/0017/000315 data/0017/000316 data/0017/000317 data/0017/000318 data/0017/000319 data/0017/000320 data/0017/000321 data/0017/000322 data/0017/000323 data/0017/000324 data/0017/000325 data/0017/000326 data/0017/000327 data/0017/000328 data/0017/000329 data/0017/000330 data/0017/000331 data/0017/000332 data/0017/000333 data/0017/000334 data/0017/000335 data/0017/000336 data/0017/000337 data/0017/000338 data/0017/000339 data/0017/000340 data/0017/000341 data/0017/000342 data/0017/000343 data/0017/000344 data/0017/000345 data/0017/000346 data/0017/000347 data/0017/000348 data/0017/000349 data/0017/000350 data/0017/000351 data/0017/000352 data/0017/000353 data/0017/000354 data/0017/000355 data/0017/000356 data/0017/000357 data/0017/000358 data/0017/000359 data/0017/000360 data/0017/000361 data/0017/000362 data/0017/000363 data/0017/000364 data/0017/000365 data/0017/000366 data/0017/000367 data/0017/000368 data/0017/000369 data/0017/000370 data/0017/000371 data/0017/000372 data/0017/000373 data/0017/000374 data/0017/000375 data/0017/000376 data/0017/000377 data/0017/000378 data/0017/000379 data/0017/000380 data/0017/000381 data/0017/000382 data/0017/000383 data/0017/000384 data/0017/000385 data/0017/000386 data/0017/000387 data/0017/000388 data/0017/000389 data/0017/000390 data/0017/000391 data/0017/000392 data/0017/000393 data/0017/000394 data/0017/000395 data/0017/000396 data/0017/000397 data/0017/000398 data/0017/000399 data/0017/000400 data/0017/000401 data/0017/000402 data/0017/000403 data/0017/000404 data/0017/000405 data/0017/000406 data/0017/000407 data/0017/000408 data/0017/000409 data/0017/000410 data/0017/000411 data/0017/000412 data/0017/000413 data/0017/000414 data/0017/000415 data/0017/000416 data/0017/000417 data/0017/000418 data/0017/000419 data/0017/000420 data/0017/000421 data/0017/000422 data/0017/000423 data/0017/000424 data/0017/000425 data/0017/000426 data/0017/000427 data/0017/000428 data/0017/000429 data/0017/000430 data/0017/000431 data/0017/000432 data/0017/000433 data/0017/000434 data/0017/000435 data/0017/000436 data/0017/000437 data/0017/000438 data/0017/000439 data/0017/000440 data/0017/000441 data/0017/000442 data/0017/000443 data/0017/000444 data/0017/000445 data/0017/000446 data/0017/000447 data/0017/000448 data/0017/000449 data/0017/000450 data/0017/000451 data/0017/000452 data/0017/000453 data/0017/000454 data/0017/000455 data/0017/000456 data/0017/000457 data/0017/000458 data/0017/000459 data/0017/000460 data/0017/000461 data/0017/000462 data/0017/000463 data/0017/000464 data/0017/000465 data/0017/000466 data/0017/000467 data/0017/000468 data/0017/000469 data/0017/000470 data/0017/000471 data/0017/000472 data/0017/000473 data/0017/000474 data/0017/000475 data/0017/000476 data/0017/000477 data/0017/000478 data/0017/000479 data/0017/000480 data/0017/000481 data/0017/000482 data/0017/000483 data/0017/000484 data/0017/000485 data/0017/000486 data/0017/000487 data/0017/000488 data/0017/000489 data/0017/000490 data/0017/000491 data/0017/000492 data/0017/000493 data/0017/000494 data/0017/000495 data/0017/000496 data/0017/000497 data/0017/000498 data/0017/000499 data/0017/000500 data/0017/000501 data/0017/000502 data/0017/000503 data/0017/000504 data/0017/000505 data/0017/000506 data/0017/000507 data/0017/000508 data/0017/000509 data/0017/000510 data/0017/000511 data/0017/000512 data/0017/000513 data/0017/000514 data/0017/000515 data/0017/000516 data/0017/000517 data/0017/000518 data/0017/000519 data/0017/000520 data/0017/000521 data/0017/000522 data/0017/000523 data/0017/000524 data/0017/000525 data/0017/000526 data/0017/000527 data/0017/000528 data/0017/000529 data/0017/000530 data/0017/000531 data/0017/000532 data/0017/000533 data/0017/000534 data/0017/000535 data/0017/000536 data/0017/000537 data/0017/000538 data/0017/000539 data/0017/000540 data/0017/000541 data/0017/000542 data/0017/000543 data/0017/000544 data/0017/000545 data/0017/000546 data/0017/000547 data/0017/000548 data/0017/000549 data/0017/000550 data/0017/000551 data/0017/000552 data/0017/000553 data/0017/000554 data/0017/000555 data/0017/000556 data/0017/000557 data/0017/000558 data/0017/000559 data/0017/000560 data/0017/000561 data/0017/000562 data/0017/000563 data/0017/000564 data/0017/000565 data/0017/000566 data/0017/000567 data/0017/000568 data/0017/000569 data/0017/000570 data/0017/000571 data/0017/000572 data/0017/000573 data/0017/000574 data/0017/000575 data/0017/000576 data/0017/000577 data/0017/000578 data/0017/000579 data/0017/000580 data/0017/000581 data/0017/000582 data/0017/000583 data/0017/000584 data/0017/000585 data/0017/000586 data/0017/000587 data/0017/000588 data/0017/000589 data/0017/000590 data/0017/000591 data/0017/000592 data/0017/000593 data/0017/000594 data/0017/000595 data/0017/000596 data/0017/000597 data/0017/000598 data/0017/000599 data/0017/000600 data/0017/000601 data/0017/000602 data/0017/000603 data/0017/000604 data/0017/000605 data/0017/000606 data/0017/000607 data/0017/000608 data/0017/000609 data/0017/000610 data/0017/000611 data/0017/000612 data/0017/000613 data/0017/000614 data/0017/000615 data/0017/000616 data/0017/000617 data/0017/000618 data/0017/000619 data/0017/000620 data/0017/000621 data/0017/000622 data/0017/000623 data/0017/000624 data/0017/000625 data/0017/000626 data/0017/000627 data/0017/000628 data/0017/000629 data/0017/000630 data/0017/000631 data/0017/000632 data/0017/000633 data/0017/000634 data/0017/000635 data/0017/000636 data/0017/000637 data/0017/000638 data/0017/000639 data/0017/000640 data/0017/000641 data/0017/000642 data/0017/000643 data/0017/000644 data/0017/000645 data/0017/000646 data/0017/000647 data/0017/000648 data/0017/000649 data/0017/000650 data/0017/000651 data/0017/000652 data/0017/000653 data/0017/000654 data/0017/000655 data/0017/000656 data/0017/000657 data/0017/000658 data/0017/000659 data/0017/000660 data/0017/000661 data/0017/000662 data/0017/000663 data/0017/000664 data/0017/000665 data/0017/000666 data/0017/000667 data/0017/000668 data/0017/000669 data/0017/000670 data/0017/000671 data/0017/000672 data/0017/000673 data/0017/000674 data/0017/000675 data/0017/000676 data/0017/000677 data/0017/000678 data/0017/000679 data/0017/000680 data/0017/000681 data/0017/000682 data/0017/000683 data/0017/000684 data/0017/000685 data/0017/000686 data/0017/000687 data/0017/000688 data/0017/000689 data/0017/000690 data/0017/000691 data/0017/000692 data/0017/000693 data/0017/000694 data/0017/000695 data/0017/000696 data/0017/000697 data/0017/000698 data/0017/000699 data/0017/000700 data/0017/000701 data/0017/000702 data/0017/000703 data/0017/000704 data/0017/000705 data/0017/000706 data/0017/000707 data/0017/000708 data/0017/000709 data/0017/000710 data/0017/000711 data/0017/000712 data/0017/000713 data/0017/000714 data/0017/000715 data/0017/000716 data/0017/000717 data/0017/000718 data/0017/000719 data/0017/000720 data/0017/000721 data/0017/000722 data/0017/000723 data/0017/000724 data/0017/000725 data/0017/000726 data/0017/000727 data/0017/000728 data/0017/000729 data/0017/000730 data/0017/000731 data/0017/000732 data/0017/000733 data/0017/000734 data/0017/000735 data/0017/000736 data/0017/000737 data/0017/000738 data/0017/000739 data/0017/000740 data/0017/000741 data/0017/000742 data/0017/000743 data/0017/000744 data/0017/000745 data/0017/000746 data/0017/000747 data/0017/000748 data/0017/000749 data/0017/000750 data/0025/000001 data/0025/000002 data/0025/000003 data/0025/000004 data/0025/000005 data/0025/000006 data/0025/000007 data/0025/000008 data/0025/000009 data/0025/000010 data/0025/000011 data/0025/000012 data/0025/000013 data/0025/000014 data/0025/000015 data/0025/000016 data/0025/000017 data/0025/000018 data/0025/000019 data/0025/000020 data/0025/000021 data/0025/000022 data/0025/000023 data/0025/000024 data/0025/000025 data/0025/000026 data/0025/000027 data/0025/000028 data/0025/000029 data/0025/000030 data/0025/000031 data/0025/000032 data/0025/000033 data/0025/000034 data/0025/000035 data/0025/000036 data/0025/000037 data/0025/000038 data/0025/000039 data/0025/000040 data/0025/000041 data/0025/000042 data/0025/000043 data/0025/000044 data/0025/000045 data/0025/000046 data/0025/000047 data/0025/000048 data/0025/000049 data/0025/000050 data/0025/000051 data/0025/000052 data/0025/000053 data/0025/000054 data/0025/000055 data/0025/000056 data/0025/000057 data/0025/000058 data/0025/000059 data/0025/000060 data/0025/000061 data/0025/000062 data/0025/000063 data/0025/000064 data/0025/000065 data/0025/000066 data/0025/000067 data/0025/000068 data/0025/000069 data/0025/000070 data/0025/000071 data/0025/000072 data/0025/000073 data/0025/000074 data/0025/000075 data/0025/000076 data/0025/000077 data/0025/000078 data/0025/000079 data/0025/000080 data/0025/000081 data/0025/000082 data/0025/000083 data/0025/000084 data/0025/000085 data/0025/000086 data/0025/000087 data/0025/000088 data/0025/000089 data/0025/000090 data/0025/000091 data/0025/000092 data/0025/000093 data/0025/000094 data/0025/000095 data/0025/000096 data/0025/000097 data/0025/000098 data/0025/000099 data/0025/000100 data/0025/000101 data/0025/000102 data/0025/000103 data/0025/000104 data/0025/000105 data/0025/000106 data/0025/000107 data/0025/000108 data/0025/000109 data/0025/000110 data/0025/000111 data/0025/000112 data/0025/000113 data/0025/000114 data/0025/000115 data/0025/000116 data/0025/000117 data/0025/000118 data/0025/000119 data/0025/000120 data/0025/000121 data/0025/000122 data/0025/000123 data/0025/000124 data/0025/000125 data/0025/000126 data/0025/000127 data/0025/000128 data/0025/000129 data/0025/000130 data/0025/000131 data/0025/000132 data/0025/000133 data/0025/000134 data/0025/000135 data/0025/000136 data/0025/000137 data/0025/000138 data/0025/000139 data/0025/000140 data/0025/000141 data/0025/000142 data/0025/000143 data/0025/000144 data/0025/000145 data/0025/000146 data/0025/000147 data/0025/000148 data/0025/000149 data/0025/000150 data/0025/000151 data/0025/000152 data/0025/000153 data/0025/000154 data/0025/000155 data/0025/000156 data/0025/000157 data/0025/000158 data/0025/000159 data/0025/000160 data/0025/000161 data/0025/000162 data/0025/000163 data/0025/000164 data/0025/000165 data/0025/000166 data/0025/000167 data/0025/000168 data/0025/000169 data/0025/000170 data/0025/000171 data/0025/000172 data/0025/000173 data/0025/000174 data/0025/000175 data/0025/000176 data/0025/000177 data/0025/000178 data/0025/000179 data/0025/000180 data/0025/000181 data/0025/000182 data/0025/000183 data/0025/000184 data/0025/000185 data/0025/000186 data/0025/000187 data/0025/000188 data/0025/000189 data/0025/000190 data/0025/000191 data/0025/000192 data/0025/000193 data/0025/000194 data/0025/000195 data/0025/000196 data/0025/000197 data/0025/000198 data/0025/000199 data/0025/000200 data/0025/000201 data/0025/000202 data/0025/000203 data/0025/000204 data/0025/000205 data/0025/000206 data/0025/000207 data/0025/000208 data/0025/000209 data/0025/000210 data/0025/000211 data/0025/000212 data/0025/000213 data/0025/000214 data/0025/000215 data/0025/000216 data/0025/000217 data/0025/000218 data/0025/000219 data/0025/000220 data/0025/000221 data/0025/000222 data/0025/000223 data/0025/000224 data/0025/000225 data/0025/000226 data/0025/000227 data/0025/000228 data/0025/000229 data/0025/000230 data/0025/000231 data/0025/000232 data/0025/000233 data/0025/000234 data/0025/000235 data/0025/000236 data/0025/000237 data/0025/000238 data/0025/000239 data/0025/000240 data/0025/000241 data/0025/000242 data/0025/000243 data/0025/000244 data/0025/000245 data/0025/000246 data/0025/000247 data/0025/000248 data/0025/000249 data/0025/000250 data/0025/000251 data/0025/000252 data/0025/000253 data/0025/000254 data/0025/000255 data/0025/000256 data/0025/000257 data/0025/000258 data/0025/000259 data/0025/000260 data/0025/000261 data/0025/000262 data/0025/000263 data/0025/000264 data/0025/000265 data/0025/000266 data/0025/000267 data/0025/000268 data/0025/000269 data/0025/000270 data/0025/000271 data/0025/000272 data/0025/000273 data/0025/000274 data/0025/000275 data/0025/000276 data/0025/000277 data/0025/000278 data/0025/000279 data/0025/000280 data/0025/000281 data/0025/000282 data/0025/000283 data/0025/000284 data/0025/000285 data/0025/000286 data/0025/000287 data/0025/000288 data/0025/000289 data/0025/000290 data/0025/000291 data/0025/000292 data/0025/000293 data/0025/000294 data/0025/000295 data/0025/000296 data/0025/000297 data/0025/000298 data/0025/000299 data/0025/000300 data/0025/000301 data/0025/000302 data/0025/000303 data/0025/000304 data/0025/000305 data/0025/000306 data/0025/000307 data/0025/000308 data/0025/000309 data/0025/000310 data/0025/000311 data/0025/000312 data/0025/000313 data/0025/000314 data/0025/000315 data/0025/000316 data/0025/000317 data/0025/000318 data/0025/000319 data/0025/000320 data/0025/000321 data/0025/000322 data/0025/000323 data/0025/000324 data/0025/000325 data/0025/000326 data/0025/000327 data/0025/000328 data/0025/000329 data/0025/000330 data/0025/000331 data/0025/000332 data/0025/000333 data/0025/000334 data/0025/000335 data/0025/000336 data/0025/000337 data/0025/000338 data/0025/000339 data/0025/000340 data/0025/000341 data/0025/000342 data/0025/000343 data/0025/000344 data/0025/000345 data/0025/000346 data/0025/000347 data/0025/000348 data/0025/000349 data/0025/000350 data/0025/000351 data/0025/000352 data/0025/000353 data/0025/000354 data/0025/000355 data/0025/000356 data/0025/000357 data/0025/000358 data/0025/000359 data/0025/000360 data/0025/000361 data/0025/000362 data/0025/000363 data/0025/000364 data/0025/000365 data/0025/000366 data/0025/000367 data/0025/000368 data/0025/000369 data/0025/000370 data/0025/000371 data/0025/000372 data/0025/000373 data/0025/000374 data/0025/000375 data/0025/000376 data/0025/000377 data/0025/000378 data/0025/000379 data/0025/000380 data/0025/000381 data/0025/000382 data/0025/000383 data/0025/000384 data/0025/000385 data/0025/000386 data/0025/000387 data/0025/000388 data/0025/000389 data/0025/000390 data/0025/000391 data/0025/000392 data/0025/000393 data/0025/000394 data/0025/000395 data/0025/000396 data/0025/000397 data/0025/000398 data/0025/000399 data/0025/000400 data/0025/000401 data/0025/000402 data/0025/000403 data/0025/000404 data/0025/000405 data/0025/000406 data/0025/000407 data/0025/000408 data/0025/000409 data/0025/000410 data/0025/000411 data/0025/000412 data/0025/000413 data/0025/000414 data/0025/000415 data/0025/000416 data/0025/000417 data/0025/000418 data/0025/000419 data/0025/000420 data/0025/000421 data/0025/000422 data/0025/000423 data/0025/000424 data/0025/000425 data/0025/000426 data/0025/000427 data/0025/000428 data/0025/000429 data/0025/000430 data/0025/000431 data/0025/000432 data/0025/000433 data/0025/000434 data/0025/000435 data/0025/000436 data/0025/000437 data/0025/000438 data/0025/000439 data/0025/000440 data/0025/000441 data/0025/000442 data/0025/000443 data/0025/000444 data/0025/000445 data/0025/000446 data/0025/000447 data/0025/000448 data/0025/000449 data/0025/000450 data/0025/000451 data/0025/000452 data/0025/000453 data/0025/000454 data/0025/000455 data/0025/000456 data/0025/000457 data/0025/000458 data/0025/000459 data/0025/000460 data/0025/000461 data/0025/000462 data/0025/000463 data/0025/000464 data/0025/000465 data/0025/000466 data/0025/000467 data/0025/000468 data/0025/000469 data/0025/000470 data/0025/000471 data/0025/000472 data/0025/000473 data/0025/000474 data/0025/000475 data/0025/000476 data/0025/000477 data/0025/000478 data/0025/000479 data/0025/000480 data/0025/000481 data/0025/000482 data/0025/000483 data/0025/000484 data/0025/000485 data/0025/000486 data/0025/000487 data/0025/000488 data/0025/000489 data/0025/000490 data/0025/000491 data/0025/000492 data/0025/000493 data/0025/000494 data/0025/000495 data/0025/000496 data/0025/000497 data/0025/000498 data/0025/000499 data/0025/000500 data/0025/000501 data/0025/000502 data/0025/000503 data/0025/000504 data/0025/000505 data/0025/000506 data/0025/000507 data/0025/000508 data/0025/000509 data/0025/000510 data/0025/000511 data/0025/000512 data/0025/000513 data/0025/000514 data/0025/000515 data/0025/000516 data/0025/000517 data/0025/000518 data/0025/000519 data/0025/000520 data/0025/000521 data/0025/000522 data/0025/000523 data/0025/000524 data/0025/000525 data/0025/000526 data/0025/000527 data/0025/000528 data/0025/000529 data/0025/000530 data/0025/000531 data/0025/000532 data/0025/000533 data/0025/000534 data/0025/000535 data/0025/000536 data/0025/000537 data/0025/000538 data/0025/000539 data/0025/000540 data/0025/000541 data/0025/000542 data/0025/000543 data/0025/000544 data/0025/000545 data/0025/000546 data/0025/000547 data/0025/000548 data/0025/000549 data/0025/000550 data/0025/000551 data/0025/000552 data/0025/000553 data/0025/000554 data/0025/000555 data/0025/000556 data/0025/000557 data/0025/000558 data/0025/000559 data/0025/000560 data/0025/000561 data/0025/000562 data/0025/000563 data/0025/000564 data/0025/000565 data/0025/000566 data/0025/000567 data/0025/000568 data/0025/000569 data/0025/000570 data/0025/000571 data/0025/000572 data/0025/000573 data/0025/000574 data/0025/000575 data/0025/000576 data/0025/000577 data/0025/000578 data/0025/000579 data/0025/000580 data/0025/000581 data/0025/000582 data/0025/000583 data/0025/000584 data/0025/000585 data/0025/000586 data/0025/000587 data/0025/000588 data/0025/000589 data/0025/000590 data/0025/000591 data/0025/000592 data/0025/000593 data/0025/000594 data/0025/000595 data/0025/000596 data/0025/000597 data/0025/000598 data/0025/000599 data/0025/000600 data/0025/000601 data/0025/000602 data/0025/000603 data/0025/000604 data/0025/000605 data/0025/000606 data/0025/000607 data/0025/000608 data/0025/000609 data/0025/000610 data/0025/000611 data/0025/000612 data/0025/000613 data/0025/000614 data/0025/000615 data/0025/000616 data/0025/000617 data/0025/000618 data/0025/000619 data/0025/000620 data/0025/000621 data/0025/000622 data/0025/000623 data/0025/000624 data/0025/000625 data/0025/000626 data/0025/000627 data/0025/000628 data/0025/000629 data/0025/000630 data/0025/000631 data/0025/000632 data/0025/000633 data/0025/000634 data/0025/000635 data/0025/000636 data/0025/000637 data/0025/000638 data/0025/000639 data/0025/000640 data/0025/000641 data/0025/000642 data/0025/000643 data/0025/000644 data/0025/000645 data/0025/000646 data/0025/000647 data/0025/000648 data/0025/000649 data/0025/000650 data/0025/000651 data/0025/000652 data/0025/000653 data/0025/000654 data/0025/000655 data/0025/000656 data/0025/000657 data/0025/000658 data/0025/000659 data/0025/000660 data/0025/000661 data/0025/000662 data/0025/000663 data/0025/000664 data/0025/000665 data/0025/000666 data/0025/000667 data/0025/000668 data/0025/000669 data/0025/000670 data/0025/000671 data/0025/000672 data/0025/000673 data/0025/000674 data/0025/000675 data/0025/000676 data/0025/000677 data/0025/000678 data/0025/000679 data/0025/000680 data/0025/000681 data/0025/000682 data/0025/000683 data/0025/000684 data/0025/000685 data/0025/000686 data/0025/000687 data/0025/000688 data/0025/000689 data/0025/000690 data/0025/000691 data/0025/000692 data/0025/000693 data/0025/000694 data/0025/000695 data/0025/000696 data/0025/000697 data/0025/000698 data/0025/000699 data/0025/000700 data/0025/000701 data/0025/000702 data/0025/000703 data/0025/000704 data/0025/000705 data/0025/000706 data/0025/000707 data/0025/000708 data/0025/000709 data/0025/000710 data/0025/000711 data/0025/000712 data/0025/000713 data/0025/000714 data/0025/000715 data/0025/000716 data/0025/000717 data/0025/000718 data/0025/000719 data/0025/000720 data/0025/000721 data/0025/000722 data/0025/000723 data/0025/000724 data/0025/000725 data/0025/000726 data/0025/000727 data/0025/000728 data/0025/000729 data/0025/000730 data/0025/000731 data/0025/000732 data/0025/000733 data/0025/000734 data/0025/000735 data/0025/000736 data/0025/000737 data/0025/000738 data/0025/000739 data/0025/000740 data/0025/000741 data/0025/000742 data/0025/000743 data/0025/000744 data/0025/000745 data/0025/000746 data/0025/000747 data/0025/000748 data/0025/000749 data/0025/000750 data/0025/000751 data/0025/000752 data/0025/000753 data/0025/000754 data/0025/000755 data/0025/000756 data/0025/000757 data/0025/000758 data/0025/000759 data/0025/000760 data/0025/000761 data/0025/000762 data/0025/000763 data/0025/000764 data/0025/000765 data/0025/000766 data/0025/000767 data/0025/000768 data/0025/000769 data/0025/000770 data/0025/000771 data/0025/000772 data/0025/000773 data/0025/000774 data/0025/000775 data/0025/000776 data/0025/000777 data/0025/000778 data/0025/000779 data/0025/000780 data/0025/000781 data/0025/000782 data/0025/000783 data/0025/000784 data/0025/000785 data/0025/000786 data/0025/000787 data/0025/000788 data/0025/000789 data/0025/000790 data/0025/000791 data/0025/000792 data/0025/000793 data/0025/000794 data/0025/000795 data/0025/000796 data/0025/000797 data/0025/000798 data/0025/000799 data/0025/000800 data/0025/000801 data/0025/000802 data/0025/000803 data/0025/000804 data/0025/000805 data/0025/000806 data/0025/000807 data/0025/000808 data/0025/000809 data/0025/000810 data/0025/000811 data/0025/000812 data/0025/000813 data/0025/000814 data/0025/000815 data/0025/000816 data/0025/000817 data/0025/000818 data/0025/000819 data/0025/000820 data/0025/000821 data/0025/000822 data/0025/000823 data/0025/000824 data/0025/000825 data/0025/000826 data/0025/000827 data/0025/000828 data/0025/000829 data/0025/000830 data/0025/000831 data/0025/000832 data/0025/000833 data/0025/000834 data/0025/000835 data/0025/000836 data/0025/000837 data/0025/000838 data/0025/000839 data/0025/000840 data/0025/000841 data/0025/000842 data/0025/000843 data/0025/000844 data/0025/000845 data/0025/000846 data/0025/000847 data/0025/000848 data/0025/000849 data/0025/000850 data/0025/000851 data/0025/000852 data/0025/000853 data/0025/000854 data/0025/000855 data/0025/000856 data/0025/000857 data/0025/000858 data/0025/000859 data/0025/000860 data/0025/000861 data/0025/000862 data/0025/000863 data/0025/000864 data/0025/000865 data/0025/000866 data/0025/000867 data/0025/000868 data/0025/000869 data/0025/000870 data/0025/000871 data/0025/000872 data/0025/000873 data/0025/000874 data/0025/000875 data/0025/000876 data/0025/000877 data/0025/000878 data/0025/000879 data/0025/000880 data/0025/000881 data/0025/000882 data/0025/000883 data/0025/000884 data/0025/000885 data/0025/000886 data/0025/000887 data/0025/000888 data/0025/000889 data/0025/000890 data/0025/000891 data/0025/000892 data/0025/000893 data/0025/000894 data/0025/000895 data/0025/000896 data/0025/000897 data/0025/000898 data/0025/000899 data/0025/000900 data/0025/000901 data/0025/000902 data/0025/000903 data/0025/000904 data/0025/000905 data/0025/000906 data/0025/000907 data/0025/000908 data/0025/000909 data/0025/000910 data/0025/000911 data/0025/000912 data/0025/000913 data/0025/000914 data/0025/000915 data/0025/000916 data/0025/000917 data/0025/000918 data/0025/000919 data/0025/000920 data/0025/000921 data/0025/000922 data/0025/000923 data/0025/000924 data/0025/000925 data/0025/000926 data/0025/000927 data/0025/000928 data/0025/000929 data/0025/000930 data/0025/000931 data/0025/000932 data/0025/000933 data/0025/000934 data/0025/000935 data/0025/000936 data/0025/000937 data/0025/000938 data/0025/000939 data/0025/000940 data/0025/000941 data/0025/000942 data/0025/000943 data/0025/000944 data/0025/000945 data/0025/000946 data/0025/000947 data/0025/000948 data/0025/000949 data/0025/000950 data/0025/000951 data/0025/000952 data/0025/000953 data/0025/000954 data/0025/000955 data/0025/000956 data/0025/000957 data/0025/000958 data/0025/000959 data/0025/000960 data/0025/000961 data/0025/000962 data/0025/000963 data/0025/000964 data/0025/000965 data/0025/000966 data/0025/000967 data/0025/000968 data/0025/000969 data/0025/000970 data/0025/000971 data/0025/000972 data/0025/000973 data/0025/000974 data/0025/000975 data/0025/000976 data/0025/000977 data/0025/000978 data/0025/000979 data/0025/000980 data/0025/000981 data/0025/000982 data/0025/000983 data/0025/000984 data/0025/000985 data/0025/000986 data/0025/000987 data/0025/000988 data/0025/000989 data/0025/000990 data/0025/000991 data/0025/000992 data/0025/000993 data/0025/000994 data/0025/000995 data/0025/000996 data/0025/000997 data/0025/000998 data/0025/000999 data/0025/001000 data/0025/001001 data/0025/001002 data/0025/001003 data/0025/001004 data/0025/001005 data/0025/001006 data/0025/001007 data/0025/001008 data/0025/001009 data/0025/001010 data/0025/001011 data/0025/001012 data/0025/001013 data/0025/001014 data/0025/001015 data/0025/001016 data/0025/001017 data/0025/001018 data/0025/001019 data/0025/001020 data/0025/001021 data/0025/001022 data/0025/001023 data/0025/001024 data/0025/001025 data/0025/001026 data/0025/001027 data/0025/001028 data/0025/001029 data/0025/001030 data/0025/001031 data/0025/001032 data/0025/001033 data/0025/001034 data/0025/001035 data/0025/001036 data/0025/001037 data/0025/001038 data/0025/001039 data/0025/001040 data/0025/001041 data/0025/001042 data/0025/001043 data/0025/001044 data/0025/001045 data/0025/001046 data/0025/001047 data/0025/001048 data/0025/001049 data/0025/001050 data/0025/001051 data/0025/001052 data/0025/001053 data/0025/001054 data/0025/001055 data/0025/001056 data/0025/001057 data/0025/001058 data/0025/001059 data/0025/001060 data/0025/001061 data/0025/001062 data/0025/001063 data/0025/001064 data/0025/001065 data/0025/001066 data/0025/001067 data/0025/001068 data/0025/001069 data/0025/001070 data/0025/001071 data/0025/001072 data/0025/001073 data/0025/001074 data/0025/001075 data/0025/001076 data/0025/001077 data/0025/001078 data/0025/001079 data/0025/001080 data/0025/001081 data/0025/001082 data/0025/001083 data/0025/001084 data/0025/001085 data/0025/001086 data/0025/001087 data/0025/001088 data/0025/001089 data/0025/001090 data/0025/001091 data/0025/001092 data/0025/001093 data/0025/001094 data/0025/001095 data/0025/001096 data/0025/001097 data/0025/001098 data/0025/001099 data/0025/001100 data/0025/001101 data/0025/001102 data/0025/001103 data/0025/001104 data/0025/001105 data/0025/001106 data/0025/001107 data/0025/001108 data/0025/001109 data/0025/001110 data/0025/001111 data/0025/001112 data/0025/001113 data/0025/001114 data/0025/001115 data/0025/001116 data/0025/001117 data/0025/001118 data/0025/001119 data/0025/001120 data/0025/001121 data/0025/001122 data/0025/001123 data/0025/001124 data/0025/001125 data/0025/001126 data/0025/001127 data/0025/001128 data/0025/001129 data/0025/001130 data/0025/001131 data/0025/001132 data/0025/001133 data/0025/001134 data/0025/001135 data/0025/001136 data/0025/001137 data/0025/001138 data/0025/001139 data/0025/001140 data/0025/001141 data/0025/001142 data/0025/001143 data/0025/001144 data/0025/001145 data/0025/001146 data/0025/001147 data/0025/001148 data/0025/001149 data/0025/001150 data/0025/001151 data/0025/001152 data/0025/001153 data/0025/001154 data/0025/001155 data/0025/001156 data/0025/001157 data/0025/001158 data/0025/001159 data/0025/001160 data/0025/001161 data/0025/001162 data/0025/001163 data/0025/001164 data/0025/001165 data/0025/001166 data/0025/001167 data/0025/001168 data/0025/001169 data/0025/001170 data/0025/001171 data/0025/001172 data/0025/001173 data/0025/001174 data/0025/001175 data/0025/001176 data/0025/001177 data/0025/001178 data/0025/001179 data/0025/001180 data/0025/001181 data/0025/001182 data/0025/001183 data/0025/001184 data/0025/001185 data/0025/001186 data/0025/001187 data/0025/001188 data/0025/001189 data/0025/001190 data/0025/001191 data/0025/001192 data/0025/001193 data/0025/001194 data/0025/001195 data/0025/001196 data/0025/001197 data/0025/001198 data/0025/001199 data/0025/001200 data/0025/001201 data/0025/001202 data/0025/001203 data/0025/001204 data/0025/001205 data/0025/001206 data/0025/001207 data/0025/001208 data/0025/001209 data/0025/001210 data/0025/001211 data/0025/001212 data/0025/001213 data/0025/001214 data/0025/001215 data/0025/001216 data/0025/001217 data/0025/001218 data/0025/001219 data/0025/001220 data/0025/001221 data/0025/001222 data/0025/001223 data/0025/001224 data/0025/001225 data/0025/001226 data/0025/001227 data/0025/001228 data/0025/001229 data/0025/001230 data/0025/001231 data/0025/001232 data/0025/001233 data/0025/001234 data/0025/001235 data/0025/001236 data/0025/001237 data/0025/001238 data/0025/001239 data/0025/001240 data/0025/001241 data/0025/001242 data/0025/001243 data/0025/001244 data/0025/001245 data/0025/001246 data/0025/001247 data/0025/001248 data/0025/001249 data/0025/001250 data/0025/001251 data/0025/001252 data/0025/001253 data/0025/001254 data/0025/001255 data/0025/001256 data/0025/001257 data/0025/001258 data/0025/001259 data/0025/001260 data/0025/001261 data/0025/001262 data/0025/001263 data/0025/001264 data/0025/001265 data/0025/001266 data/0025/001267 data/0025/001268 data/0025/001269 data/0025/001270 data/0025/001271 data/0025/001272 data/0025/001273 data/0025/001274 data/0025/001275 data/0025/001276 data/0025/001277 data/0025/001278 data/0025/001279 data/0025/001280 data/0025/001281 data/0025/001282 data/0025/001283 data/0025/001284 data/0025/001285 data/0025/001286 data/0025/001287 data/0025/001288 data/0025/001289 data/0025/001290 data/0025/001291 data/0025/001292 data/0025/001293 data/0025/001294 data/0025/001295 data/0025/001296 data/0025/001297 data/0025/001298 data/0025/001299 data/0025/001300 data/0025/001301 data/0025/001302 data/0025/001303 data/0025/001304 data/0025/001305 data/0025/001306 data/0025/001307 data/0025/001308 data/0025/001309 data/0025/001310 data/0025/001311 data/0025/001312 data/0025/001313 data/0025/001314 data/0025/001315 data/0025/001316 data/0025/001317 data/0025/001318 data/0025/001319 data/0025/001320 data/0025/001321 data/0025/001322 data/0025/001323 data/0025/001324 data/0025/001325 data/0025/001326 data/0025/001327 data/0025/001328 data/0025/001329 data/0025/001330 data/0025/001331 data/0025/001332 data/0025/001333 data/0025/001334 data/0025/001335 data/0025/001336 data/0025/001337 data/0025/001338 data/0025/001339 data/0025/001340 data/0025/001341 data/0025/001342 data/0025/001343 data/0025/001344 data/0025/001345 data/0025/001346 data/0025/001347 data/0025/001348 data/0025/001349 data/0025/001350 data/0025/001351 data/0025/001352 data/0025/001353 data/0025/001354 data/0025/001355 data/0025/001356 data/0025/001357 data/0025/001358 data/0025/001359 data/0025/001360 data/0025/001361 data/0025/001362 data/0025/001363 data/0025/001364 data/0025/001365 data/0025/001366 data/0025/001367 data/0025/001368 data/0025/001369 data/0025/001370 data/0025/001371 data/0025/001372 data/0025/001373 data/0025/001374 data/0025/001375 data/0025/001376 data/0025/001377 data/0025/001378 data/0025/001379 data/0025/001380 data/0025/001381 data/0025/001382 data/0025/001383 data/0025/001384 data/0025/001385 data/0025/001386 data/0025/001387 data/0025/001388 data/0025/001389 data/0025/001390 data/0025/001391 data/0025/001392 data/0025/001393 data/0025/001394 data/0025/001395 data/0025/001396 data/0025/001397 data/0025/001398 data/0025/001399 data/0025/001400 data/0025/001401 data/0025/001402 data/0025/001403 data/0025/001404 data/0025/001405 data/0025/001406 data/0025/001407 data/0025/001408 data/0025/001409 data/0025/001410 data/0025/001411 data/0025/001412 data/0025/001413 data/0025/001414 data/0025/001415 data/0025/001416 data/0025/001417 data/0025/001418 data/0025/001419 data/0025/001420 data/0025/001421 data/0025/001422 data/0025/001423 data/0025/001424 data/0025/001425 data/0025/001426 data/0025/001427 data/0025/001428 data/0025/001429 data/0025/001430 data/0025/001431 data/0025/001432 data/0025/001433 data/0025/001434 data/0025/001435 data/0025/001436 data/0025/001437 data/0025/001438 data/0025/001439 data/0025/001440 data/0025/001441 data/0025/001442 data/0025/001443 data/0025/001444 data/0025/001445 data/0025/001446 data/0025/001447 data/0025/001448 data/0025/001449 data/0025/001450 data/0025/001451 data/0025/001452 data/0025/001453 data/0025/001454 data/0025/001455 data/0025/001456 data/0025/001457 data/0025/001458 data/0025/001459 data/0025/001460 data/0025/001461 data/0025/001462 data/0025/001463 data/0025/001464 data/0025/001465 data/0025/001466 data/0025/001467 data/0025/001468 data/0025/001469 data/0025/001470 data/0025/001471 data/0025/001472 data/0025/001473 data/0025/001474 data/0025/001475 data/0025/001476 data/0025/001477 data/0025/001478 data/0025/001479 data/0025/001480 data/0025/001481 data/0025/001482 data/0025/001483 data/0025/001484 data/0025/001485 data/0025/001486 data/0025/001487 data/0025/001488 data/0025/001489 data/0025/001490 data/0025/001491 data/0025/001492 data/0025/001493 data/0025/001494 data/0025/001495 data/0039/000001 data/0039/000002 data/0039/000003 data/0039/000004 data/0039/000005 data/0039/000006 data/0039/000007 data/0039/000008 data/0039/000009 data/0039/000010 data/0039/000011 data/0039/000012 data/0039/000013 data/0039/000014 data/0039/000015 data/0039/000016 data/0039/000017 data/0039/000018 data/0039/000019 data/0039/000020 data/0039/000021 data/0039/000022 data/0039/000023 data/0039/000024 data/0039/000025 data/0039/000026 data/0039/000027 data/0039/000028 data/0039/000029 data/0039/000030 data/0039/000031 data/0039/000032 data/0039/000033 data/0039/000034 data/0039/000035 data/0039/000036 data/0039/000037 data/0039/000038 data/0039/000039 data/0039/000040 data/0039/000041 data/0039/000042 data/0039/000043 data/0039/000044 data/0039/000045 data/0039/000046 data/0039/000047 data/0039/000048 data/0039/000049 data/0039/000050 data/0039/000051 data/0039/000052 data/0039/000053 data/0039/000054 data/0039/000055 data/0039/000056 data/0039/000057 data/0039/000058 data/0039/000059 data/0039/000060 data/0039/000061 data/0039/000062 data/0039/000063 data/0039/000064 data/0039/000065 data/0039/000066 data/0039/000067 data/0039/000068 data/0039/000069 data/0039/000070 data/0039/000071 data/0039/000072 data/0039/000073 data/0039/000074 data/0039/000075 data/0039/000076 data/0039/000077 data/0039/000078 data/0039/000079 data/0039/000080 data/0039/000081 data/0039/000082 data/0039/000083 data/0039/000084 data/0039/000085 data/0039/000086 data/0039/000087 data/0039/000088 data/0039/000089 data/0039/000090 data/0039/000091 data/0039/000092 data/0039/000093 data/0039/000094 data/0039/000095 data/0039/000096 data/0039/000097 data/0039/000098 data/0039/000099 data/0039/000100 data/0039/000101 data/0039/000102 data/0039/000103 data/0039/000104 data/0039/000105 data/0039/000106 data/0039/000107 data/0039/000108 data/0039/000109 data/0039/000110 data/0039/000111 data/0039/000112 data/0039/000113 data/0039/000114 data/0039/000115 data/0039/000116 data/0039/000117 data/0039/000118 data/0039/000119 data/0039/000120 data/0039/000121 data/0039/000122 data/0039/000123 data/0039/000124 data/0039/000125 data/0039/000126 data/0039/000127 data/0039/000128 data/0039/000129 data/0039/000130 data/0039/000131 data/0039/000132 data/0039/000133 data/0039/000134 data/0039/000135 data/0039/000136 data/0039/000137 data/0039/000138 data/0039/000139 data/0039/000140 data/0039/000141 data/0039/000142 data/0039/000143 data/0039/000144 data/0039/000145 data/0039/000146 data/0039/000147 data/0039/000148 data/0039/000149 data/0039/000150 data/0039/000151 data/0039/000152 data/0039/000153 data/0039/000154 data/0039/000155 data/0039/000156 data/0039/000157 data/0039/000158 data/0039/000159 data/0039/000160 data/0039/000161 data/0039/000162 data/0039/000163 data/0039/000164 data/0039/000165 data/0039/000166 data/0039/000167 data/0039/000168 data/0039/000169 data/0039/000170 data/0039/000171 data/0039/000172 data/0039/000173 data/0039/000174 data/0039/000175 data/0039/000176 data/0039/000177 data/0039/000178 data/0039/000179 data/0039/000180 data/0039/000181 data/0039/000182 data/0039/000183 data/0039/000184 data/0039/000185 data/0039/000186 data/0039/000187 data/0039/000188 data/0039/000189 data/0039/000190 data/0039/000191 data/0039/000192 data/0039/000193 data/0039/000194 data/0039/000195 data/0039/000196 data/0039/000197 data/0039/000198 data/0039/000199 data/0039/000200 data/0039/000201 data/0039/000202 data/0039/000203 data/0039/000204 data/0039/000205 data/0039/000206 data/0039/000207 data/0039/000208 data/0039/000209 data/0039/000210 data/0039/000211 data/0039/000212 data/0039/000213 data/0039/000214 data/0039/000215 data/0039/000216 data/0039/000217 data/0039/000218 data/0039/000219 data/0039/000220 data/0039/000221 data/0039/000222 data/0039/000223 data/0039/000224 data/0039/000225 data/0039/000226 data/0039/000227 data/0039/000228 data/0039/000229 data/0039/000230 data/0039/000231 data/0039/000232 data/0039/000233 data/0039/000234 data/0039/000235 data/0039/000236 data/0039/000237 data/0039/000238 data/0039/000239 data/0039/000240 data/0039/000241 data/0039/000242 data/0039/000243 data/0039/000244 data/0039/000245 data/0039/000246 data/0039/000247 data/0039/000248 data/0039/000249 data/0039/000250 data/0039/000251 data/0039/000252 data/0039/000253 data/0039/000254 data/0039/000255 data/0039/000256 data/0039/000257 data/0039/000258 data/0039/000259 data/0039/000260 data/0039/000261 data/0039/000262 data/0039/000263 data/0039/000264 data/0039/000265 data/0039/000266 data/0039/000267 data/0039/000268 data/0039/000269 data/0039/000270 data/0039/000271 data/0039/000272 data/0039/000273 data/0039/000274 data/0039/000275 data/0039/000276 data/0039/000277 data/0039/000278 data/0039/000279 data/0039/000280 data/0039/000281 data/0039/000282 data/0039/000283 data/0039/000284 data/0039/000285 data/0039/000286 data/0039/000287 data/0039/000288 data/0039/000289 data/0039/000290 data/0039/000291 data/0039/000292 data/0039/000293 data/0039/000294 data/0039/000295 data/0039/000296 data/0039/000297 data/0039/000298 data/0039/000299 data/0039/000300 data/0039/000301 data/0039/000302 data/0039/000303 data/0039/000304 data/0039/000305 data/0039/000306 data/0039/000307 data/0039/000308 data/0039/000309 data/0039/000310 data/0039/000311 data/0039/000312 data/0039/000313 data/0039/000314 data/0039/000315 data/0039/000316 data/0039/000317 data/0039/000318 data/0039/000319 data/0039/000320 data/0039/000321 data/0039/000322 data/0039/000323 data/0039/000324 data/0039/000325 data/0039/000326 data/0039/000327 data/0039/000328 data/0039/000329 data/0039/000330 data/0039/000331 data/0039/000332 data/0039/000333 data/0039/000334 data/0039/000335 data/0039/000336 data/0039/000337 data/0039/000338 data/0039/000339 data/0039/000340 data/0039/000341 data/0039/000342 data/0039/000343 data/0039/000344 data/0039/000345 data/0039/000346 data/0039/000347 data/0039/000348 data/0039/000349 data/0039/000350 data/0039/000351 data/0039/000352 data/0039/000353 data/0039/000354 data/0039/000355 data/0039/000356 data/0039/000357 data/0039/000358 data/0039/000359 data/0039/000360 data/0039/000361 data/0039/000362 data/0039/000363 data/0039/000364 data/0039/000365 data/0039/000366 data/0039/000367 data/0039/000368 data/0039/000369 data/0039/000370 data/0039/000371 data/0039/000372 data/0039/000373 data/0039/000374 data/0039/000375 data/0039/000376 data/0039/000377 data/0039/000378 data/0039/000379 data/0039/000380 data/0039/000381 data/0039/000382 data/0039/000383 data/0039/000384 data/0039/000385 data/0039/000386 data/0039/000387 data/0039/000388 data/0039/000389 data/0039/000390 data/0039/000391 data/0039/000392 data/0039/000393 data/0039/000394 data/0039/000395 data/0039/000396 data/0039/000397 data/0039/000398 data/0039/000399 data/0039/000400 data/0039/000401 data/0039/000402 data/0039/000403 data/0039/000404 data/0039/000405 data/0039/000406 data/0039/000407 data/0039/000408 data/0039/000409 data/0039/000410 data/0039/000411 data/0039/000412 data/0039/000413 data/0039/000414 data/0039/000415 data/0039/000416 data/0039/000417 data/0039/000418 data/0039/000419 data/0039/000420 data/0039/000421 data/0039/000422 data/0039/000423 data/0039/000424 data/0039/000425 data/0039/000426 data/0039/000427 data/0039/000428 data/0039/000429 data/0039/000430 data/0039/000431 data/0039/000432 data/0039/000433 data/0039/000434 data/0039/000435 data/0039/000436 data/0039/000437 data/0039/000438 data/0039/000439 data/0039/000440 data/0039/000441 data/0039/000442 data/0039/000443 data/0039/000444 data/0039/000445 data/0039/000446 data/0039/000447 data/0039/000448 data/0039/000449 data/0039/000450 data/0039/000451 data/0039/000452 data/0039/000453 data/0039/000454 data/0039/000455 data/0039/000456 data/0039/000457 data/0039/000458 data/0039/000459 data/0039/000460 data/0039/000461 data/0039/000462 data/0039/000463 data/0039/000464 data/0039/000465 data/0039/000466 data/0039/000467 data/0039/000468 data/0039/000469 data/0039/000470 data/0039/000471 data/0039/000472 data/0039/000473 data/0039/000474 data/0039/000475 data/0039/000476 data/0039/000477 data/0039/000478 data/0039/000479 data/0039/000480 data/0039/000481 data/0039/000482 data/0039/000483 data/0039/000484 data/0039/000485 data/0039/000486 data/0039/000487 data/0039/000488 data/0039/000489 data/0039/000490 data/0039/000491 data/0039/000492 data/0039/000493 data/0039/000494 data/0039/000495 data/0039/000496 data/0039/000497 data/0039/000498 data/0039/000499 data/0039/000500 data/0039/000501 data/0039/000502 data/0039/000503 data/0039/000504 data/0039/000505 data/0039/000506 data/0039/000507 data/0039/000508 data/0039/000509 data/0039/000510 data/0039/000511 data/0039/000512 data/0039/000513 data/0039/000514 data/0039/000515 data/0039/000516 data/0039/000517 data/0039/000518 data/0039/000519 data/0039/000520 data/0039/000521 data/0039/000522 data/0039/000523 data/0039/000524 data/0039/000525 data/0039/000526 data/0039/000527 data/0039/000528 data/0039/000529 data/0039/000530 data/0039/000531 data/0039/000532 data/0039/000533 data/0039/000534 data/0039/000535 data/0039/000536 data/0039/000537 data/0039/000538 data/0039/000539 data/0039/000540 data/0039/000541 data/0039/000542 data/0039/000543 data/0039/000544 data/0039/000545 data/0039/000546 data/0039/000547 data/0039/000548 data/0039/000549 data/0039/000550 data/0039/000551 data/0039/000552 data/0039/000553 data/0039/000554 data/0039/000555 data/0039/000556 data/0039/000557 data/0039/000558 data/0039/000559 data/0039/000560 data/0039/000561 data/0039/000562 data/0039/000563 data/0039/000564 data/0039/000565 data/0039/000566 data/0039/000567 data/0039/000568 data/0039/000569 data/0039/000570 data/0039/000571 data/0039/000572 data/0039/000573 data/0039/000574 data/0039/000575 data/0039/000576 data/0039/000577 data/0039/000578 data/0039/000579 data/0039/000580 data/0039/000581 data/0039/000582 data/0039/000583 data/0039/000584 data/0039/000585 data/0039/000586 data/0039/000587 data/0039/000588 data/0039/000589 data/0039/000590 data/0039/000591 data/0039/000592 data/0039/000593 data/0039/000594 data/0039/000595 data/0039/000596 data/0039/000597 data/0039/000598 data/0039/000599 data/0039/000600 data/0039/000601 data/0039/000602 data/0039/000603 data/0039/000604 data/0039/000605 data/0039/000606 data/0039/000607 data/0039/000608 data/0039/000609 data/0039/000610 data/0039/000611 data/0039/000612 data/0039/000613 data/0039/000614 data/0039/000615 data/0039/000616 data/0039/000617 data/0039/000618 data/0039/000619 data/0039/000620 data/0039/000621 data/0039/000622 data/0039/000623 data/0039/000624 data/0039/000625 data/0039/000626 data/0039/000627 data/0039/000628 data/0039/000629 data/0039/000630 data/0039/000631 data/0039/000632 data/0039/000633 data/0039/000634 data/0039/000635 data/0039/000636 data/0039/000637 data/0039/000638 data/0039/000639 data/0039/000640 data/0039/000641 data/0039/000642 data/0039/000643 data/0039/000644 data/0039/000645 data/0039/000646 data/0039/000647 data/0039/000648 data/0039/000649 data/0039/000650 data/0039/000651 data/0039/000652 data/0039/000653 data/0039/000654 data/0039/000655 data/0039/000656 data/0039/000657 data/0039/000658 data/0039/000659 data/0039/000660 data/0039/000661 data/0039/000662 data/0039/000663 data/0039/000664 data/0039/000665 data/0039/000666 data/0039/000667 data/0039/000668 data/0039/000669 data/0039/000670 data/0039/000671 data/0039/000672 data/0039/000673 data/0039/000674 data/0039/000675 data/0039/000676 data/0039/000677 data/0039/000678 data/0039/000679 data/0039/000680 data/0039/000681 data/0039/000682 data/0039/000683 data/0039/000684 data/0039/000685 data/0039/000686 data/0039/000687 data/0039/000688 data/0039/000689 data/0039/000690 data/0039/000691 data/0039/000692 data/0039/000693 data/0039/000694 data/0039/000695 data/0039/000696 data/0039/000697 data/0039/000698 data/0039/000699 data/0039/000700 data/0039/000701 data/0039/000702 data/0039/000703 data/0039/000704 data/0039/000705 data/0039/000706 data/0039/000707 data/0039/000708 data/0039/000709 data/0039/000710 data/0039/000711 data/0039/000712 data/0039/000713 data/0039/000714 data/0039/000715 data/0039/000716 data/0039/000717 data/0039/000718 data/0039/000719 data/0039/000720 data/0039/000721 data/0039/000722 data/0039/000723 data/0039/000724 data/0039/000725 data/0039/000726 data/0039/000727 data/0039/000728 data/0039/000729 data/0039/000730 data/0039/000731 data/0039/000732 data/0039/000733 data/0039/000734 data/0039/000735 data/0039/000736 data/0039/000737 data/0039/000738 data/0039/000739 data/0039/000740 data/0039/000741 data/0039/000742 data/0039/000743 data/0039/000744 data/0039/000745 data/0039/000746 data/0039/000747 data/0039/000748 data/0039/000749 data/0039/000750 data/0039/000751 data/0039/000752 data/0039/000753 data/0039/000754 data/0039/000755 data/0039/000756 data/0039/000757 data/0039/000758 data/0039/000759 data/0039/000760 data/0039/000761 data/0039/000762 data/0039/000763 data/0039/000764 data/0039/000765 data/0039/000766 data/0039/000767 data/0039/000768 data/0039/000769 data/0039/000770 data/0039/000771 data/0039/000772 data/0039/000773 data/0039/000774 data/0039/000775 data/0039/000776 data/0039/000777 data/0039/000778 data/0039/000779 data/0039/000780 data/0039/000781 data/0039/000782 data/0039/000783 data/0039/000784 data/0039/000785 data/0039/000786 data/0039/000787 data/0039/000788 data/0039/000789 data/0039/000790 data/0039/000791 data/0039/000792 data/0039/000793 data/0039/000794 data/0039/000795 data/0039/000796 data/0039/000797 data/0039/000798 data/0039/000799 data/0039/000800 data/0039/000801 data/0039/000802 data/0039/000803 data/0039/000804 data/0039/000805 data/0039/000806 data/0039/000807 data/0039/000808 data/0039/000809 data/0039/000810 data/0039/000811 data/0039/000812 data/0039/000813 data/0039/000814 data/0039/000815 data/0039/000816 data/0039/000817 data/0039/000818 data/0039/000819 data/0039/000820 data/0039/000821 data/0039/000822 data/0039/000823 data/0039/000824 data/0039/000825 data/0039/000826 data/0039/000827 data/0039/000828 data/0039/000829 data/0039/000830 data/0039/000831 data/0039/000832 data/0039/000833 data/0039/000834 data/0039/000835 data/0039/000836 data/0039/000837 data/0039/000838 data/0039/000839 data/0039/000840 data/0039/000841 data/0039/000842 data/0039/000843 data/0039/000844 data/0039/000845 data/0039/000846 data/0039/000847 data/0039/000848 data/0039/000849 data/0039/000850 data/0039/000851 data/0039/000852 data/0039/000853 data/0039/000854 data/0039/000855 data/0039/000856 data/0039/000857 data/0039/000858 data/0039/000859 data/0039/000860 data/0039/000861 data/0039/000862 data/0039/000863 data/0039/000864 data/0039/000865 data/0039/000866 data/0039/000867 data/0039/000868 data/0039/000869 data/0039/000870 data/0039/000871 data/0039/000872 data/0039/000873 data/0039/000874 data/0039/000875 data/0039/000876 data/0039/000877 data/0039/000878 data/0039/000879 data/0039/000880 data/0039/000881 data/0039/000882 data/0039/000883 data/0039/000884 data/0039/000885 data/0039/000886 data/0039/000887 data/0039/000888 data/0039/000889 data/0039/000890 data/0039/000891 data/0039/000892 data/0039/000893 data/0039/000894 data/0039/000895 data/0039/000896 data/0039/000897 data/0039/000898 data/0039/000899 data/0039/000900 data/0039/000901 data/0039/000902 data/0039/000903 data/0039/000904 data/0039/000905 data/0039/000906 data/0039/000907 data/0039/000908 data/0039/000909 data/0039/000910 data/0039/000911 data/0039/000912 data/0039/000913 data/0039/000914 data/0039/000915 data/0039/000916 data/0039/000917 data/0039/000918 data/0039/000919 data/0039/000920 data/0039/000921 data/0039/000922 data/0039/000923 data/0039/000924 data/0039/000925 data/0039/000926 data/0039/000927 data/0039/000928 data/0039/000929 data/0039/000930 data/0039/000931 data/0039/000932 data/0039/000933 data/0039/000934 data/0039/000935 data/0039/000936 data/0039/000937 data/0039/000938 data/0039/000939 data/0039/000940 data/0039/000941 data/0039/000942 data/0039/000943 data/0039/000944 data/0039/000945 data/0039/000946 data/0039/000947 data/0039/000948 data/0039/000949 data/0039/000950 data/0039/000951 data/0039/000952 data/0039/000953 data/0039/000954 data/0039/000955 data/0039/000956 data/0039/000957 data/0039/000958 data/0039/000959 data/0039/000960 data/0039/000961 data/0039/000962 data/0039/000963 data/0039/000964 data/0039/000965 data/0039/000966 data/0039/000967 data/0039/000968 data/0039/000969 data/0039/000970 data/0039/000971 data/0039/000972 data/0039/000973 data/0039/000974 data/0039/000975 data/0039/000976 data/0039/000977 data/0039/000978 data/0039/000979 data/0039/000980 data/0039/000981 data/0039/000982 data/0039/000983 data/0039/000984 data/0039/000985 data/0039/000986 data/0039/000987 data/0039/000988 data/0039/000989 data/0039/000990 data/0039/000991 data/0039/000992 data/0039/000993 data/0039/000994 data/0039/000995 data/0039/000996 data/0039/000997 data/0039/000998 data/0039/000999 data/0039/001000 data/0039/001001 data/0039/001002 data/0039/001003 data/0039/001004 data/0039/001005 data/0039/001006 data/0039/001007 data/0039/001008 data/0039/001009 data/0039/001010 data/0039/001011 data/0039/001012 data/0039/001013 data/0039/001014 data/0039/001015 data/0039/001016 data/0039/001017 data/0039/001018 data/0039/001019 data/0039/001020 data/0039/001021 data/0039/001022 data/0039/001023 data/0039/001024 data/0039/001025 data/0039/001026 data/0039/001027 data/0039/001028 data/0039/001029 data/0039/001030 data/0039/001031 data/0039/001032 data/0039/001033 data/0039/001034 data/0039/001035 data/0039/001036 data/0039/001037 data/0039/001038 data/0039/001039 data/0039/001040 data/0039/001041 data/0039/001042 data/0039/001043 data/0039/001044 data/0039/001045 data/0039/001046 data/0039/001047 data/0039/001048 data/0039/001049 data/0039/001050 data/0039/001051 data/0039/001052 data/0039/001053 data/0039/001054 data/0039/001055 data/0039/001056 data/0039/001057 data/0039/001058 data/0039/001059 data/0039/001060 data/0039/001061 data/0039/001062 data/0039/001063 data/0039/001064 data/0039/001065 data/0039/001066 data/0039/001067 data/0039/001068 data/0039/001069 data/0039/001070 data/0039/001071 data/0039/001072 data/0039/001073 data/0039/001074 data/0039/001075 data/0039/001076 data/0039/001077 data/0039/001078 data/0039/001079 data/0039/001080 data/0039/001081 data/0039/001082 data/0039/001083 data/0039/001084 data/0039/001085 data/0039/001086 data/0039/001087 data/0039/001088 data/0039/001089 data/0039/001090 data/0039/001091 ================================================ FILE: DenseFusion/datasets/warehouse/dataset_config/train_data_list.txt ================================================ data/0000/000001 data/0000/000002 data/0000/000003 data/0000/000004 data/0000/000005 data/0000/000006 data/0000/000007 data/0000/000008 data/0000/000009 data/0000/000010 data/0000/000011 data/0000/000012 data/0000/000013 data/0000/000014 data/0000/000015 data/0000/000016 data/0000/000017 data/0000/000018 data/0000/000019 data/0000/000020 data/0000/000021 data/0000/000022 data/0000/000023 data/0000/000024 data/0000/000025 data/0000/000026 data/0000/000027 data/0000/000028 data/0000/000029 data/0000/000030 data/0000/000031 data/0000/000032 data/0000/000033 data/0000/000034 data/0000/000035 data/0000/000036 data/0000/000037 data/0000/000038 data/0000/000039 data/0000/000040 data/0000/000041 data/0000/000042 data/0000/000043 data/0000/000044 data/0000/000045 data/0000/000046 data/0000/000047 data/0000/000048 data/0000/000049 data/0000/000050 data/0000/000051 data/0000/000052 data/0000/000053 data/0000/000054 data/0000/000055 data/0000/000056 data/0000/000057 data/0000/000058 data/0000/000059 data/0000/000060 data/0000/000061 data/0000/000062 data/0000/000063 data/0000/000064 data/0000/000065 data/0000/000066 data/0000/000067 data/0000/000068 data/0000/000069 data/0000/000070 data/0000/000071 data/0000/000072 data/0000/000073 data/0000/000074 data/0000/000075 data/0000/000076 data/0000/000077 data/0000/000078 data/0000/000079 data/0000/000080 data/0000/000081 data/0000/000082 data/0000/000083 data/0000/000084 data/0000/000085 data/0000/000086 data/0000/000087 data/0000/000088 data/0000/000089 data/0000/000090 data/0000/000091 data/0000/000092 data/0000/000093 data/0000/000094 data/0000/000095 data/0000/000096 data/0000/000097 data/0000/000098 data/0000/000099 data/0000/000100 data/0000/000101 data/0000/000102 data/0000/000103 data/0000/000104 data/0000/000105 data/0000/000106 data/0000/000107 data/0000/000108 data/0000/000109 data/0000/000110 data/0000/000111 data/0000/000112 data/0000/000113 data/0000/000114 data/0000/000115 data/0000/000116 data/0000/000117 data/0000/000118 data/0000/000119 data/0000/000120 data/0000/000121 data/0000/000122 data/0000/000123 data/0000/000124 data/0000/000125 data/0000/000126 data/0000/000127 data/0000/000128 data/0000/000129 data/0000/000130 data/0000/000131 data/0000/000132 data/0000/000133 data/0000/000134 data/0000/000135 data/0000/000136 data/0000/000137 data/0000/000138 data/0000/000139 data/0000/000140 data/0000/000141 data/0000/000142 data/0000/000143 data/0000/000144 data/0000/000145 data/0000/000146 data/0000/000147 data/0000/000148 data/0000/000149 data/0000/000150 data/0000/000151 data/0000/000152 data/0000/000153 data/0000/000154 data/0000/000155 data/0000/000156 data/0000/000157 data/0000/000158 data/0000/000159 data/0000/000160 data/0000/000161 data/0000/000162 data/0000/000163 data/0000/000164 data/0000/000165 data/0000/000166 data/0000/000167 data/0000/000168 data/0000/000169 data/0000/000170 data/0000/000171 data/0000/000172 data/0000/000173 data/0000/000174 data/0000/000175 data/0000/000176 data/0000/000177 data/0000/000178 data/0000/000179 data/0000/000180 data/0000/000181 data/0000/000182 data/0000/000183 data/0000/000184 data/0000/000185 data/0000/000186 data/0000/000187 data/0000/000188 data/0000/000189 data/0000/000190 data/0000/000191 data/0000/000192 data/0000/000193 data/0000/000194 data/0000/000195 data/0000/000196 data/0000/000197 data/0000/000198 data/0000/000199 data/0000/000200 data/0000/000201 data/0000/000202 data/0000/000203 data/0000/000204 data/0000/000205 data/0000/000206 data/0000/000207 data/0000/000208 data/0000/000209 data/0000/000210 data/0000/000211 data/0000/000212 data/0000/000213 data/0000/000214 data/0000/000215 data/0000/000216 data/0000/000217 data/0000/000218 data/0000/000219 data/0000/000220 data/0000/000221 data/0000/000222 data/0000/000223 data/0000/000224 data/0000/000225 data/0000/000226 data/0000/000227 data/0000/000228 data/0000/000229 data/0000/000230 data/0000/000231 data/0000/000232 data/0000/000233 data/0000/000234 data/0000/000235 data/0000/000236 data/0000/000237 data/0000/000238 data/0000/000239 data/0000/000240 data/0000/000241 data/0000/000242 data/0000/000243 data/0000/000244 data/0000/000245 data/0000/000246 data/0000/000247 data/0000/000248 data/0000/000249 data/0000/000250 data/0000/000251 data/0000/000252 data/0000/000253 data/0000/000254 data/0000/000255 data/0000/000256 data/0000/000257 data/0000/000258 data/0000/000259 data/0000/000260 data/0000/000261 data/0000/000262 data/0000/000263 data/0000/000264 data/0000/000265 data/0000/000266 data/0000/000267 data/0000/000268 data/0000/000269 data/0000/000270 data/0000/000271 data/0000/000272 data/0000/000273 data/0000/000274 data/0000/000275 data/0000/000276 data/0000/000277 data/0000/000278 data/0000/000279 data/0000/000280 data/0000/000281 data/0000/000282 data/0000/000283 data/0000/000284 data/0000/000285 data/0000/000286 data/0000/000287 data/0000/000288 data/0000/000289 data/0000/000290 data/0000/000291 data/0000/000292 data/0000/000293 data/0000/000294 data/0000/000295 data/0000/000296 data/0000/000297 data/0000/000298 data/0000/000299 data/0000/000300 data/0000/000301 data/0000/000302 data/0000/000303 data/0000/000304 data/0000/000305 data/0000/000306 data/0000/000307 data/0000/000308 data/0000/000309 data/0000/000310 data/0000/000311 data/0000/000312 data/0000/000313 data/0000/000314 data/0000/000315 data/0000/000316 data/0000/000317 data/0000/000318 data/0000/000319 data/0000/000320 data/0000/000321 data/0000/000322 data/0000/000323 data/0000/000324 data/0000/000325 data/0000/000326 data/0000/000327 data/0000/000328 data/0000/000329 data/0000/000330 data/0000/000331 data/0000/000332 data/0000/000333 data/0000/000334 data/0000/000335 data/0000/000336 data/0000/000337 data/0000/000338 data/0000/000339 data/0000/000340 data/0000/000341 data/0000/000342 data/0000/000343 data/0000/000344 data/0000/000345 data/0000/000346 data/0000/000347 data/0000/000348 data/0000/000349 data/0000/000350 data/0000/000351 data/0000/000352 data/0000/000353 data/0000/000354 data/0000/000355 data/0000/000356 data/0000/000357 data/0000/000358 data/0000/000359 data/0000/000360 data/0000/000361 data/0000/000362 data/0000/000363 data/0000/000364 data/0000/000365 data/0000/000366 data/0000/000367 data/0000/000368 data/0000/000369 data/0000/000370 data/0000/000371 data/0000/000372 data/0000/000373 data/0000/000374 data/0000/000375 data/0000/000376 data/0000/000377 data/0000/000378 data/0000/000379 data/0000/000380 data/0000/000381 data/0000/000382 data/0000/000383 data/0000/000384 data/0000/000385 data/0000/000386 data/0000/000387 data/0000/000388 data/0000/000389 data/0000/000390 data/0000/000391 data/0000/000392 data/0000/000393 data/0000/000394 data/0000/000395 data/0000/000396 data/0000/000397 data/0000/000398 data/0000/000399 data/0000/000400 data/0000/000401 data/0000/000402 data/0000/000403 data/0000/000404 data/0000/000405 data/0000/000406 data/0000/000407 data/0000/000408 data/0000/000409 data/0000/000410 data/0000/000411 data/0000/000412 data/0000/000413 data/0000/000414 data/0000/000415 data/0000/000416 data/0000/000417 data/0000/000418 data/0000/000419 data/0000/000420 data/0000/000421 data/0000/000422 data/0000/000423 data/0000/000424 data/0000/000425 data/0000/000426 data/0000/000427 data/0000/000428 data/0000/000429 data/0000/000430 data/0000/000431 data/0000/000432 data/0000/000433 data/0000/000434 data/0000/000435 data/0000/000436 data/0000/000437 data/0000/000438 data/0000/000439 data/0000/000440 data/0000/000441 data/0000/000442 data/0000/000443 data/0000/000444 data/0000/000445 data/0000/000446 data/0000/000447 data/0000/000448 data/0000/000449 data/0000/000450 data/0000/000451 data/0000/000452 data/0000/000453 data/0000/000454 data/0000/000455 data/0000/000456 data/0000/000457 data/0000/000458 data/0000/000459 data/0000/000460 data/0000/000461 data/0000/000462 data/0000/000463 data/0000/000464 data/0000/000465 data/0000/000466 data/0000/000467 data/0000/000468 data/0000/000469 data/0000/000470 data/0000/000471 data/0000/000472 data/0000/000473 data/0000/000474 data/0000/000475 data/0000/000476 data/0000/000477 data/0000/000478 data/0000/000479 data/0000/000480 data/0000/000481 data/0000/000482 data/0000/000483 data/0000/000484 data/0000/000485 data/0000/000486 data/0000/000487 data/0000/000488 data/0000/000489 data/0000/000490 data/0000/000491 data/0000/000492 data/0000/000493 data/0000/000494 data/0000/000495 data/0000/000496 data/0000/000497 data/0000/000498 data/0000/000499 data/0000/000500 data/0000/000501 data/0000/000502 data/0000/000503 data/0000/000504 data/0000/000505 data/0000/000506 data/0000/000507 data/0000/000508 data/0000/000509 data/0000/000510 data/0000/000511 data/0000/000512 data/0000/000513 data/0000/000514 data/0000/000515 data/0000/000516 data/0000/000517 data/0000/000518 data/0000/000519 data/0000/000520 data/0000/000521 data/0000/000522 data/0000/000523 data/0000/000524 data/0000/000525 data/0000/000526 data/0000/000527 data/0000/000528 data/0000/000529 data/0000/000530 data/0000/000531 data/0000/000532 data/0000/000533 data/0000/000534 data/0000/000535 data/0000/000536 data/0000/000537 data/0000/000538 data/0000/000539 data/0000/000540 data/0000/000541 data/0000/000542 data/0000/000543 data/0000/000544 data/0000/000545 data/0000/000546 data/0000/000547 data/0000/000548 data/0000/000549 data/0000/000550 data/0000/000551 data/0000/000552 data/0000/000553 data/0000/000554 data/0000/000555 data/0000/000556 data/0000/000557 data/0000/000558 data/0000/000559 data/0000/000560 data/0000/000561 data/0000/000562 data/0000/000563 data/0000/000564 data/0000/000565 data/0000/000566 data/0000/000567 data/0000/000568 data/0000/000569 data/0000/000570 data/0000/000571 data/0000/000572 data/0000/000573 data/0000/000574 data/0000/000575 data/0000/000576 data/0000/000577 data/0000/000578 data/0000/000579 data/0000/000580 data/0000/000581 data/0000/000582 data/0000/000583 data/0000/000584 data/0000/000585 data/0000/000586 data/0000/000587 data/0000/000588 data/0000/000589 data/0000/000590 data/0000/000591 data/0000/000592 data/0000/000593 data/0000/000594 data/0000/000595 data/0000/000596 data/0000/000597 data/0000/000598 data/0000/000599 data/0000/000600 data/0000/000601 data/0000/000602 data/0000/000603 data/0000/000604 data/0000/000605 data/0000/000606 data/0000/000607 data/0000/000608 data/0000/000609 data/0000/000610 data/0000/000611 data/0000/000612 data/0000/000613 data/0000/000614 data/0000/000615 data/0000/000616 data/0000/000617 data/0000/000618 data/0000/000619 data/0000/000620 data/0000/000621 data/0000/000622 data/0000/000623 data/0000/000624 data/0000/000625 data/0000/000626 data/0000/000627 data/0000/000628 data/0000/000629 data/0000/000630 data/0000/000631 data/0000/000632 data/0000/000633 data/0000/000634 data/0000/000635 data/0000/000636 data/0000/000637 data/0000/000638 data/0000/000639 data/0000/000640 data/0000/000641 data/0000/000642 data/0000/000643 data/0000/000644 data/0000/000645 data/0000/000646 data/0000/000647 data/0000/000648 data/0000/000649 data/0000/000650 data/0000/000651 data/0000/000652 data/0000/000653 data/0000/000654 data/0000/000655 data/0000/000656 data/0000/000657 data/0000/000658 data/0000/000659 data/0000/000660 data/0000/000661 data/0000/000662 data/0000/000663 data/0000/000664 data/0000/000665 data/0000/000666 data/0000/000667 data/0000/000668 data/0000/000669 data/0000/000670 data/0000/000671 data/0000/000672 data/0000/000673 data/0000/000674 data/0000/000675 data/0000/000676 data/0000/000677 data/0000/000678 data/0000/000679 data/0000/000680 data/0000/000681 data/0000/000682 data/0000/000683 data/0000/000684 data/0000/000685 data/0000/000686 data/0000/000687 data/0000/000688 data/0000/000689 data/0000/000690 data/0000/000691 data/0000/000692 data/0000/000693 data/0000/000694 data/0000/000695 data/0000/000696 data/0000/000697 data/0000/000698 data/0000/000699 data/0000/000700 data/0000/000701 data/0000/000702 data/0000/000703 data/0000/000704 data/0000/000705 data/0000/000706 data/0000/000707 data/0000/000708 data/0000/000709 data/0000/000710 data/0000/000711 data/0000/000712 data/0000/000713 data/0000/000714 data/0000/000715 data/0000/000716 data/0000/000717 data/0000/000718 data/0000/000719 data/0000/000720 data/0000/000721 data/0000/000722 data/0000/000723 data/0000/000724 data/0000/000725 data/0000/000726 data/0000/000727 data/0000/000728 data/0000/000729 data/0000/000730 data/0000/000731 data/0000/000732 data/0000/000733 data/0000/000734 data/0000/000735 data/0000/000736 data/0000/000737 data/0000/000738 data/0000/000739 data/0000/000740 data/0000/000741 data/0000/000742 data/0000/000743 data/0000/000744 data/0000/000745 data/0000/000746 data/0000/000747 data/0000/000748 data/0000/000749 data/0000/000750 data/0000/000751 data/0000/000752 data/0000/000753 data/0000/000754 data/0000/000755 data/0000/000756 data/0000/000757 data/0000/000758 data/0000/000759 data/0000/000760 data/0000/000761 data/0000/000762 data/0000/000763 data/0000/000764 data/0000/000765 data/0000/000766 data/0000/000767 data/0000/000768 data/0000/000769 data/0000/000770 data/0000/000771 data/0000/000772 data/0000/000773 data/0000/000774 data/0000/000775 data/0000/000776 data/0000/000777 data/0000/000778 data/0000/000779 data/0000/000780 data/0000/000781 data/0000/000782 data/0000/000783 data/0000/000784 data/0000/000785 data/0000/000786 data/0000/000787 data/0000/000788 data/0000/000789 data/0000/000790 data/0000/000791 data/0000/000792 data/0000/000793 data/0000/000794 data/0000/000795 data/0000/000796 data/0000/000797 data/0000/000798 data/0000/000799 data/0000/000800 data/0000/000801 data/0000/000802 data/0000/000803 data/0000/000804 data/0000/000805 data/0000/000806 data/0000/000807 data/0000/000808 data/0000/000809 data/0000/000810 data/0000/000811 data/0000/000812 data/0000/000813 data/0000/000814 data/0000/000815 data/0000/000816 data/0000/000817 data/0000/000818 data/0000/000819 data/0000/000820 data/0000/000821 data/0000/000822 data/0000/000823 data/0000/000824 data/0000/000825 data/0000/000826 data/0000/000827 data/0000/000828 data/0000/000829 data/0000/000830 data/0000/000831 data/0000/000832 data/0000/000833 data/0000/000834 data/0000/000835 data/0000/000836 data/0000/000837 data/0000/000838 data/0000/000839 data/0000/000840 data/0000/000841 data/0000/000842 data/0000/000843 data/0000/000844 data/0000/000845 data/0000/000846 data/0000/000847 data/0000/000848 data/0000/000849 data/0000/000850 data/0000/000851 data/0000/000852 data/0000/000853 data/0000/000854 data/0000/000855 data/0000/000856 data/0000/000857 data/0000/000858 data/0000/000859 data/0000/000860 data/0000/000861 data/0000/000862 data/0000/000863 data/0000/000864 data/0000/000865 data/0000/000866 data/0000/000867 data/0000/000868 data/0000/000869 data/0000/000870 data/0000/000871 data/0000/000872 data/0000/000873 data/0000/000874 data/0000/000875 data/0000/000876 data/0000/000877 data/0000/000878 data/0000/000879 data/0000/000880 data/0000/000881 data/0000/000882 data/0000/000883 data/0000/000884 data/0000/000885 data/0000/000886 data/0000/000887 data/0000/000888 data/0000/000889 data/0000/000890 data/0000/000891 data/0000/000892 data/0000/000893 data/0000/000894 data/0000/000895 data/0000/000896 data/0000/000897 data/0000/000898 data/0000/000899 data/0000/000900 data/0000/000901 data/0000/000902 data/0000/000903 data/0000/000904 data/0000/000905 data/0000/000906 data/0000/000907 data/0000/000908 data/0000/000909 data/0000/000910 data/0000/000911 data/0000/000912 data/0000/000913 data/0000/000914 data/0000/000915 data/0000/000916 data/0000/000917 data/0000/000918 data/0000/000919 data/0000/000920 data/0000/000921 data/0000/000922 data/0000/000923 data/0000/000924 data/0000/000925 data/0000/000926 data/0000/000927 data/0000/000928 data/0000/000929 data/0000/000930 data/0000/000931 data/0000/000932 data/0000/000933 data/0000/000934 data/0000/000935 data/0000/000936 data/0000/000937 data/0000/000938 data/0000/000939 data/0000/000940 data/0000/000941 data/0000/000942 data/0000/000943 data/0000/000944 data/0000/000945 data/0000/000946 data/0000/000947 data/0000/000948 data/0000/000949 data/0000/000950 data/0000/000951 data/0000/000952 data/0000/000953 data/0000/000954 data/0000/000955 data/0000/000956 data/0000/000957 data/0000/000958 data/0000/000959 data/0000/000960 data/0000/000961 data/0000/000962 data/0000/000963 data/0000/000964 data/0000/000965 data/0000/000966 data/0000/000967 data/0000/000968 data/0000/000969 data/0000/000970 data/0000/000971 data/0000/000972 data/0000/000973 data/0000/000974 data/0000/000975 data/0000/000976 data/0000/000977 data/0000/000978 data/0000/000979 data/0000/000980 data/0000/000981 data/0000/000982 data/0000/000983 data/0000/000984 data/0000/000985 data/0000/000986 data/0000/000987 data/0000/000988 data/0000/000989 data/0000/000990 data/0000/000991 data/0000/000992 data/0000/000993 data/0000/000994 data/0000/000995 data/0000/000996 data/0000/000997 data/0000/000998 data/0000/000999 data/0000/001000 data/0000/001001 data/0000/001002 data/0000/001003 data/0000/001004 data/0000/001005 data/0000/001006 data/0000/001007 data/0000/001008 data/0000/001009 data/0000/001010 data/0000/001011 data/0000/001012 data/0000/001013 data/0000/001014 data/0000/001015 data/0000/001016 data/0000/001017 data/0000/001018 data/0000/001019 data/0000/001020 data/0000/001021 data/0000/001022 data/0000/001023 data/0000/001024 data/0000/001025 data/0000/001026 data/0000/001027 data/0000/001028 data/0000/001029 data/0000/001030 data/0000/001031 data/0000/001032 data/0000/001033 data/0000/001034 data/0000/001035 data/0000/001036 data/0000/001037 data/0000/001038 data/0000/001039 data/0000/001040 data/0000/001041 data/0000/001042 data/0000/001043 data/0000/001044 data/0000/001045 data/0000/001046 data/0000/001047 data/0000/001048 data/0000/001049 data/0000/001050 data/0000/001051 data/0000/001052 data/0000/001053 data/0000/001054 data/0000/001055 data/0000/001056 data/0000/001057 data/0000/001058 data/0000/001059 data/0000/001060 data/0000/001061 data/0000/001062 data/0000/001063 data/0000/001064 data/0000/001065 data/0000/001066 data/0000/001067 data/0000/001068 data/0000/001069 data/0000/001070 data/0000/001071 data/0000/001072 data/0000/001073 data/0000/001074 data/0000/001075 data/0000/001076 data/0000/001077 data/0000/001078 data/0000/001079 data/0000/001080 data/0000/001081 data/0000/001082 data/0000/001083 data/0000/001084 data/0000/001085 data/0000/001086 data/0000/001087 data/0000/001088 data/0000/001089 data/0000/001090 data/0000/001091 data/0000/001092 data/0000/001093 data/0000/001094 data/0000/001095 data/0000/001096 data/0000/001097 data/0000/001098 data/0000/001099 data/0000/001100 data/0000/001101 data/0000/001102 data/0000/001103 data/0000/001104 data/0000/001105 data/0000/001106 data/0000/001107 data/0000/001108 data/0000/001109 data/0000/001110 data/0000/001111 data/0000/001112 data/0000/001113 data/0000/001114 data/0000/001115 data/0000/001116 data/0000/001117 data/0000/001118 data/0000/001119 data/0000/001120 data/0000/001121 data/0000/001122 data/0000/001123 data/0000/001124 data/0000/001125 data/0000/001126 data/0000/001127 data/0000/001128 data/0000/001129 data/0000/001130 data/0000/001131 data/0000/001132 data/0000/001133 data/0000/001134 data/0000/001135 data/0000/001136 data/0000/001137 data/0000/001138 data/0000/001139 data/0000/001140 data/0000/001141 data/0000/001142 data/0000/001143 data/0000/001144 data/0000/001145 data/0000/001146 data/0000/001147 data/0000/001148 data/0000/001149 data/0000/001150 data/0000/001151 data/0000/001152 data/0000/001153 data/0000/001154 data/0000/001155 data/0000/001156 data/0000/001157 data/0000/001158 data/0000/001159 data/0000/001160 data/0000/001161 data/0000/001162 data/0000/001163 data/0000/001164 data/0000/001165 data/0000/001166 data/0000/001167 data/0000/001168 data/0000/001169 data/0000/001170 data/0000/001171 data/0000/001172 data/0000/001173 data/0001/000001 data/0001/000002 data/0001/000003 data/0001/000004 data/0001/000005 data/0001/000006 data/0001/000007 data/0001/000008 data/0001/000009 data/0001/000010 data/0001/000011 data/0001/000012 data/0001/000013 data/0001/000014 data/0001/000015 data/0001/000016 data/0001/000017 data/0001/000018 data/0001/000019 data/0001/000020 data/0001/000021 data/0001/000022 data/0001/000023 data/0001/000024 data/0001/000025 data/0001/000026 data/0001/000027 data/0001/000028 data/0001/000029 data/0001/000030 data/0001/000031 data/0001/000032 data/0001/000033 data/0001/000034 data/0001/000035 data/0001/000036 data/0001/000037 data/0001/000038 data/0001/000039 data/0001/000040 data/0001/000041 data/0001/000042 data/0001/000043 data/0001/000044 data/0001/000045 data/0001/000046 data/0001/000047 data/0001/000048 data/0001/000049 data/0001/000050 data/0001/000051 data/0001/000052 data/0001/000053 data/0001/000054 data/0001/000055 data/0001/000056 data/0001/000057 data/0001/000058 data/0001/000059 data/0001/000060 data/0001/000061 data/0001/000062 data/0001/000063 data/0001/000064 data/0001/000065 data/0001/000066 data/0001/000067 data/0001/000068 data/0001/000069 data/0001/000070 data/0001/000071 data/0001/000072 data/0001/000073 data/0001/000074 data/0001/000075 data/0001/000076 data/0001/000077 data/0001/000078 data/0001/000079 data/0001/000080 data/0001/000081 data/0001/000082 data/0001/000083 data/0001/000084 data/0001/000085 data/0001/000086 data/0001/000087 data/0001/000088 data/0001/000089 data/0001/000090 data/0001/000091 data/0001/000092 data/0001/000093 data/0001/000094 data/0001/000095 data/0001/000096 data/0001/000097 data/0001/000098 data/0001/000099 data/0001/000100 data/0001/000101 data/0001/000102 data/0001/000103 data/0001/000104 data/0001/000105 data/0001/000106 data/0001/000107 data/0001/000108 data/0001/000109 data/0001/000110 data/0001/000111 data/0001/000112 data/0001/000113 data/0001/000114 data/0001/000115 data/0001/000116 data/0001/000117 data/0001/000118 data/0001/000119 data/0001/000120 data/0001/000121 data/0001/000122 data/0001/000123 data/0001/000124 data/0001/000125 data/0001/000126 data/0001/000127 data/0001/000128 data/0001/000129 data/0001/000130 data/0001/000131 data/0001/000132 data/0001/000133 data/0001/000134 data/0001/000135 data/0001/000136 data/0001/000137 data/0001/000138 data/0001/000139 data/0001/000140 data/0001/000141 data/0001/000142 data/0001/000143 data/0001/000144 data/0001/000145 data/0001/000146 data/0001/000147 data/0001/000148 data/0001/000149 data/0001/000150 data/0001/000151 data/0001/000152 data/0001/000153 data/0001/000154 data/0001/000155 data/0001/000156 data/0001/000157 data/0001/000158 data/0001/000159 data/0001/000160 data/0001/000161 data/0001/000162 data/0001/000163 data/0001/000164 data/0001/000165 data/0001/000166 data/0001/000167 data/0001/000168 data/0001/000169 data/0001/000170 data/0001/000171 data/0001/000172 data/0001/000173 data/0001/000174 data/0001/000175 data/0001/000176 data/0001/000177 data/0001/000178 data/0001/000179 data/0001/000180 data/0001/000181 data/0001/000182 data/0001/000183 data/0001/000184 data/0001/000185 data/0001/000186 data/0001/000187 data/0001/000188 data/0001/000189 data/0001/000190 data/0001/000191 data/0001/000192 data/0001/000193 data/0001/000194 data/0001/000195 data/0001/000196 data/0001/000197 data/0001/000198 data/0001/000199 data/0001/000200 data/0001/000201 data/0001/000202 data/0001/000203 data/0001/000204 data/0001/000205 data/0001/000206 data/0001/000207 data/0001/000208 data/0001/000209 data/0001/000210 data/0001/000211 data/0001/000212 data/0001/000213 data/0001/000214 data/0001/000215 data/0001/000216 data/0001/000217 data/0001/000218 data/0001/000219 data/0001/000220 data/0001/000221 data/0001/000222 data/0001/000223 data/0001/000224 data/0001/000225 data/0001/000226 data/0001/000227 data/0001/000228 data/0001/000229 data/0001/000230 data/0001/000231 data/0001/000232 data/0001/000233 data/0001/000234 data/0001/000235 data/0001/000236 data/0001/000237 data/0001/000238 data/0001/000239 data/0001/000240 data/0001/000241 data/0001/000242 data/0001/000243 data/0001/000244 data/0001/000245 data/0001/000246 data/0001/000247 data/0001/000248 data/0001/000249 data/0001/000250 data/0001/000251 data/0001/000252 data/0001/000253 data/0001/000254 data/0001/000255 data/0001/000256 data/0001/000257 data/0001/000258 data/0001/000259 data/0001/000260 data/0001/000261 data/0001/000262 data/0001/000263 data/0001/000264 data/0001/000265 data/0001/000266 data/0001/000267 data/0001/000268 data/0001/000269 data/0001/000270 data/0001/000271 data/0001/000272 data/0001/000273 data/0001/000274 data/0001/000275 data/0001/000276 data/0001/000277 data/0001/000278 data/0001/000279 data/0001/000280 data/0001/000281 data/0001/000282 data/0001/000283 data/0001/000284 data/0001/000285 data/0001/000286 data/0001/000287 data/0001/000288 data/0001/000289 data/0001/000290 data/0001/000291 data/0001/000292 data/0001/000293 data/0001/000294 data/0001/000295 data/0001/000296 data/0001/000297 data/0001/000298 data/0001/000299 data/0001/000300 data/0001/000301 data/0001/000302 data/0001/000303 data/0001/000304 data/0001/000305 data/0001/000306 data/0001/000307 data/0001/000308 data/0001/000309 data/0001/000310 data/0001/000311 data/0001/000312 data/0001/000313 data/0001/000314 data/0001/000315 data/0001/000316 data/0001/000317 data/0001/000318 data/0001/000319 data/0001/000320 data/0001/000321 data/0001/000322 data/0001/000323 data/0001/000324 data/0001/000325 data/0001/000326 data/0001/000327 data/0001/000328 data/0001/000329 data/0001/000330 data/0001/000331 data/0001/000332 data/0001/000333 data/0001/000334 data/0001/000335 data/0001/000336 data/0001/000337 data/0001/000338 data/0001/000339 data/0001/000340 data/0001/000341 data/0001/000342 data/0001/000343 data/0001/000344 data/0001/000345 data/0001/000346 data/0001/000347 data/0001/000348 data/0001/000349 data/0001/000350 data/0001/000351 data/0001/000352 data/0001/000353 data/0001/000354 data/0001/000355 data/0001/000356 data/0001/000357 data/0001/000358 data/0001/000359 data/0001/000360 data/0001/000361 data/0001/000362 data/0001/000363 data/0001/000364 data/0001/000365 data/0001/000366 data/0001/000367 data/0001/000368 data/0001/000369 data/0001/000370 data/0001/000371 data/0001/000372 data/0001/000373 data/0001/000374 data/0001/000375 data/0001/000376 data/0001/000377 data/0001/000378 data/0001/000379 data/0001/000380 data/0001/000381 data/0001/000382 data/0001/000383 data/0001/000384 data/0001/000385 data/0001/000386 data/0001/000387 data/0001/000388 data/0001/000389 data/0001/000390 data/0001/000391 data/0001/000392 data/0001/000393 data/0001/000394 data/0001/000395 data/0001/000396 data/0001/000397 data/0001/000398 data/0001/000399 data/0001/000400 data/0001/000401 data/0001/000402 data/0001/000403 data/0001/000404 data/0001/000405 data/0001/000406 data/0001/000407 data/0001/000408 data/0001/000409 data/0001/000410 data/0001/000411 data/0001/000412 data/0001/000413 data/0001/000414 data/0001/000415 data/0001/000416 data/0001/000417 data/0001/000418 data/0001/000419 data/0001/000420 data/0001/000421 data/0001/000422 data/0001/000423 data/0001/000424 data/0001/000425 data/0001/000426 data/0001/000427 data/0001/000428 data/0001/000429 data/0001/000430 data/0001/000431 data/0001/000432 data/0001/000433 data/0001/000434 data/0001/000435 data/0001/000436 data/0001/000437 data/0001/000438 data/0001/000439 data/0001/000440 data/0001/000441 data/0001/000442 data/0001/000443 data/0001/000444 data/0001/000445 data/0001/000446 data/0001/000447 data/0001/000448 data/0001/000449 data/0001/000450 data/0001/000451 data/0001/000452 data/0001/000453 data/0001/000454 data/0001/000455 data/0001/000456 data/0001/000457 data/0001/000458 data/0001/000459 data/0001/000460 data/0001/000461 data/0001/000462 data/0001/000463 data/0001/000464 data/0001/000465 data/0001/000466 data/0001/000467 data/0001/000468 data/0001/000469 data/0001/000470 data/0001/000471 data/0001/000472 data/0001/000473 data/0001/000474 data/0001/000475 data/0001/000476 data/0001/000477 data/0001/000478 data/0001/000479 data/0001/000480 data/0001/000481 data/0001/000482 data/0001/000483 data/0001/000484 data/0001/000485 data/0001/000486 data/0001/000487 data/0001/000488 data/0001/000489 data/0001/000490 data/0001/000491 data/0001/000492 data/0001/000493 data/0001/000494 data/0001/000495 data/0001/000496 data/0001/000497 data/0001/000498 data/0001/000499 data/0001/000500 data/0001/000501 data/0001/000502 data/0001/000503 data/0001/000504 data/0001/000505 data/0001/000506 data/0001/000507 data/0001/000508 data/0001/000509 data/0001/000510 data/0001/000511 data/0001/000512 data/0001/000513 data/0001/000514 data/0001/000515 data/0001/000516 data/0001/000517 data/0001/000518 data/0001/000519 data/0001/000520 data/0001/000521 data/0001/000522 data/0001/000523 data/0001/000524 data/0001/000525 data/0001/000526 data/0001/000527 data/0001/000528 data/0001/000529 data/0001/000530 data/0001/000531 data/0001/000532 data/0001/000533 data/0001/000534 data/0001/000535 data/0001/000536 data/0001/000537 data/0001/000538 data/0001/000539 data/0001/000540 data/0001/000541 data/0001/000542 data/0001/000543 data/0001/000544 data/0001/000545 data/0001/000546 data/0001/000547 data/0001/000548 data/0001/000549 data/0001/000550 data/0001/000551 data/0001/000552 data/0001/000553 data/0001/000554 data/0001/000555 data/0001/000556 data/0001/000557 data/0001/000558 data/0001/000559 data/0001/000560 data/0001/000561 data/0001/000562 data/0001/000563 data/0001/000564 data/0001/000565 data/0001/000566 data/0001/000567 data/0001/000568 data/0001/000569 data/0001/000570 data/0001/000571 data/0001/000572 data/0001/000573 data/0001/000574 data/0001/000575 data/0001/000576 data/0001/000577 data/0001/000578 data/0001/000579 data/0001/000580 data/0001/000581 data/0001/000582 data/0001/000583 data/0001/000584 data/0001/000585 data/0001/000586 data/0001/000587 data/0001/000588 data/0001/000589 data/0001/000590 data/0001/000591 data/0001/000592 data/0001/000593 data/0001/000594 data/0001/000595 data/0001/000596 data/0001/000597 data/0001/000598 data/0001/000599 data/0001/000600 data/0001/000601 data/0001/000602 data/0001/000603 data/0001/000604 data/0001/000605 data/0001/000606 data/0001/000607 data/0001/000608 data/0001/000609 data/0001/000610 data/0001/000611 data/0001/000612 data/0001/000613 data/0001/000614 data/0001/000615 data/0001/000616 data/0001/000617 data/0001/000618 data/0001/000619 data/0001/000620 data/0001/000621 data/0001/000622 data/0001/000623 data/0001/000624 data/0001/000625 data/0001/000626 data/0001/000627 data/0001/000628 data/0001/000629 data/0001/000630 data/0001/000631 data/0001/000632 data/0001/000633 data/0001/000634 data/0001/000635 data/0001/000636 data/0001/000637 data/0001/000638 data/0001/000639 data/0001/000640 data/0001/000641 data/0001/000642 data/0001/000643 data/0001/000644 data/0001/000645 data/0001/000646 data/0001/000647 data/0001/000648 data/0001/000649 data/0001/000650 data/0001/000651 data/0001/000652 data/0001/000653 data/0001/000654 data/0001/000655 data/0001/000656 data/0001/000657 data/0001/000658 data/0001/000659 data/0001/000660 data/0001/000661 data/0001/000662 data/0001/000663 data/0001/000664 data/0001/000665 data/0001/000666 data/0001/000667 data/0001/000668 data/0001/000669 data/0001/000670 data/0001/000671 data/0001/000672 data/0001/000673 data/0001/000674 data/0001/000675 data/0001/000676 data/0001/000677 data/0001/000678 data/0001/000679 data/0001/000680 data/0001/000681 data/0001/000682 data/0001/000683 data/0001/000684 data/0001/000685 data/0001/000686 data/0001/000687 data/0001/000688 data/0001/000689 data/0001/000690 data/0001/000691 data/0001/000692 data/0001/000693 data/0001/000694 data/0001/000695 data/0001/000696 data/0001/000697 data/0001/000698 data/0001/000699 data/0001/000700 data/0001/000701 data/0001/000702 data/0001/000703 data/0001/000704 data/0001/000705 data/0001/000706 data/0001/000707 data/0001/000708 data/0001/000709 data/0001/000710 data/0001/000711 data/0001/000712 data/0001/000713 data/0001/000714 data/0001/000715 data/0001/000716 data/0001/000717 data/0001/000718 data/0001/000719 data/0001/000720 data/0001/000721 data/0001/000722 data/0001/000723 data/0001/000724 data/0001/000725 data/0001/000726 data/0001/000727 data/0001/000728 data/0001/000729 data/0001/000730 data/0001/000731 data/0001/000732 data/0001/000733 data/0001/000734 data/0001/000735 data/0001/000736 data/0001/000737 data/0001/000738 data/0001/000739 data/0001/000740 data/0001/000741 data/0001/000742 data/0001/000743 data/0001/000744 data/0001/000745 data/0001/000746 data/0001/000747 data/0001/000748 data/0001/000749 data/0001/000750 data/0001/000751 data/0001/000752 data/0001/000753 data/0001/000754 data/0001/000755 data/0001/000756 data/0001/000757 data/0001/000758 data/0001/000759 data/0001/000760 data/0001/000761 data/0001/000762 data/0001/000763 data/0001/000764 data/0001/000765 data/0001/000766 data/0001/000767 data/0001/000768 data/0001/000769 data/0001/000770 data/0001/000771 data/0001/000772 data/0001/000773 data/0001/000774 data/0001/000775 data/0001/000776 data/0001/000777 data/0001/000778 data/0001/000779 data/0001/000780 data/0001/000781 data/0001/000782 data/0001/000783 data/0001/000784 data/0001/000785 data/0001/000786 data/0001/000787 data/0001/000788 data/0001/000789 data/0001/000790 data/0001/000791 data/0001/000792 data/0001/000793 data/0001/000794 data/0001/000795 data/0001/000796 data/0001/000797 data/0001/000798 data/0001/000799 data/0001/000800 data/0001/000801 data/0001/000802 data/0001/000803 data/0001/000804 data/0001/000805 data/0001/000806 data/0001/000807 data/0001/000808 data/0001/000809 data/0001/000810 data/0001/000811 data/0001/000812 data/0001/000813 data/0001/000814 data/0001/000815 data/0001/000816 data/0001/000817 data/0001/000818 data/0001/000819 data/0001/000820 data/0001/000821 data/0001/000822 data/0001/000823 data/0001/000824 data/0001/000825 data/0001/000826 data/0001/000827 data/0001/000828 data/0001/000829 data/0001/000830 data/0001/000831 data/0001/000832 data/0001/000833 data/0001/000834 data/0001/000835 data/0001/000836 data/0001/000837 data/0001/000838 data/0001/000839 data/0001/000840 data/0001/000841 data/0001/000842 data/0001/000843 data/0001/000844 data/0001/000845 data/0001/000846 data/0001/000847 data/0001/000848 data/0001/000849 data/0001/000850 data/0001/000851 data/0001/000852 data/0001/000853 data/0001/000854 data/0001/000855 data/0001/000856 data/0001/000857 data/0001/000858 data/0001/000859 data/0001/000860 data/0001/000861 data/0001/000862 data/0001/000863 data/0001/000864 data/0001/000865 data/0001/000866 data/0001/000867 data/0001/000868 data/0001/000869 data/0001/000870 data/0001/000871 data/0001/000872 data/0001/000873 data/0001/000874 data/0001/000875 data/0001/000876 data/0001/000877 data/0001/000878 data/0001/000879 data/0001/000880 data/0001/000881 data/0001/000882 data/0001/000883 data/0001/000884 data/0001/000885 data/0001/000886 data/0001/000887 data/0001/000888 data/0001/000889 data/0001/000890 data/0001/000891 data/0001/000892 data/0001/000893 data/0001/000894 data/0001/000895 data/0001/000896 data/0001/000897 data/0001/000898 data/0001/000899 data/0001/000900 data/0001/000901 data/0001/000902 data/0001/000903 data/0001/000904 data/0001/000905 data/0001/000906 data/0001/000907 data/0001/000908 data/0001/000909 data/0001/000910 data/0001/000911 data/0001/000912 data/0001/000913 data/0001/000914 data/0001/000915 data/0001/000916 data/0001/000917 data/0001/000918 data/0001/000919 data/0001/000920 data/0001/000921 data/0001/000922 data/0001/000923 data/0001/000924 data/0001/000925 data/0001/000926 data/0001/000927 data/0001/000928 data/0001/000929 data/0001/000930 data/0001/000931 data/0001/000932 data/0001/000933 data/0001/000934 data/0001/000935 data/0001/000936 data/0001/000937 data/0001/000938 data/0001/000939 data/0001/000940 data/0001/000941 data/0001/000942 data/0001/000943 data/0001/000944 data/0001/000945 data/0001/000946 data/0001/000947 data/0001/000948 data/0001/000949 data/0001/000950 data/0001/000951 data/0001/000952 data/0001/000953 data/0001/000954 data/0001/000955 data/0001/000956 data/0001/000957 data/0001/000958 data/0001/000959 data/0001/000960 data/0001/000961 data/0001/000962 data/0001/000963 data/0001/000964 data/0001/000965 data/0001/000966 data/0001/000967 data/0001/000968 data/0001/000969 data/0001/000970 data/0001/000971 data/0001/000972 data/0001/000973 data/0001/000974 data/0001/000975 data/0001/000976 data/0001/000977 data/0001/000978 data/0001/000979 data/0001/000980 data/0001/000981 data/0001/000982 data/0001/000983 data/0001/000984 data/0001/000985 data/0001/000986 data/0001/000987 data/0001/000988 data/0001/000989 data/0001/000990 data/0001/000991 data/0001/000992 data/0001/000993 data/0001/000994 data/0001/000995 data/0002/000001 data/0002/000002 data/0002/000003 data/0002/000004 data/0002/000005 data/0002/000006 data/0002/000007 data/0002/000008 data/0002/000009 data/0002/000010 data/0002/000011 data/0002/000012 data/0002/000013 data/0002/000014 data/0002/000015 data/0002/000016 data/0002/000017 data/0002/000018 data/0002/000019 data/0002/000020 data/0002/000021 data/0002/000022 data/0002/000023 data/0002/000024 data/0002/000025 data/0002/000026 data/0002/000027 data/0002/000028 data/0002/000029 data/0002/000030 data/0002/000031 data/0002/000032 data/0002/000033 data/0002/000034 data/0002/000035 data/0002/000036 data/0002/000037 data/0002/000038 data/0002/000039 data/0002/000040 data/0002/000041 data/0002/000042 data/0002/000043 data/0002/000044 data/0002/000045 data/0002/000046 data/0002/000047 data/0002/000048 data/0002/000049 data/0002/000050 data/0002/000051 data/0002/000052 data/0002/000053 data/0002/000054 data/0002/000055 data/0002/000056 data/0002/000057 data/0002/000058 data/0002/000059 data/0002/000060 data/0002/000061 data/0002/000062 data/0002/000063 data/0002/000064 data/0002/000065 data/0002/000066 data/0002/000067 data/0002/000068 data/0002/000069 data/0002/000070 data/0002/000071 data/0002/000072 data/0002/000073 data/0002/000074 data/0002/000075 data/0002/000076 data/0002/000077 data/0002/000078 data/0002/000079 data/0002/000080 data/0002/000081 data/0002/000082 data/0002/000083 data/0002/000084 data/0002/000085 data/0002/000086 data/0002/000087 data/0002/000088 data/0002/000089 data/0002/000090 data/0002/000091 data/0002/000092 data/0002/000093 data/0002/000094 data/0002/000095 data/0002/000096 data/0002/000097 data/0002/000098 data/0002/000099 data/0002/000100 data/0002/000101 data/0002/000102 data/0002/000103 data/0002/000104 data/0002/000105 data/0002/000106 data/0002/000107 data/0002/000108 data/0002/000109 data/0002/000110 data/0002/000111 data/0002/000112 data/0002/000113 data/0002/000114 data/0002/000115 data/0002/000116 data/0002/000117 data/0002/000118 data/0002/000119 data/0002/000120 data/0002/000121 data/0002/000122 data/0002/000123 data/0002/000124 data/0002/000125 data/0002/000126 data/0002/000127 data/0002/000128 data/0002/000129 data/0002/000130 data/0002/000131 data/0002/000132 data/0002/000133 data/0002/000134 data/0002/000135 data/0002/000136 data/0002/000137 data/0002/000138 data/0002/000139 data/0002/000140 data/0002/000141 data/0002/000142 data/0002/000143 data/0002/000144 data/0002/000145 data/0002/000146 data/0002/000147 data/0002/000148 data/0002/000149 data/0002/000150 data/0002/000151 data/0002/000152 data/0002/000153 data/0002/000154 data/0002/000155 data/0002/000156 data/0002/000157 data/0002/000158 data/0002/000159 data/0002/000160 data/0002/000161 data/0002/000162 data/0002/000163 data/0002/000164 data/0002/000165 data/0002/000166 data/0002/000167 data/0002/000168 data/0002/000169 data/0002/000170 data/0002/000171 data/0002/000172 data/0002/000173 data/0002/000174 data/0002/000175 data/0002/000176 data/0002/000177 data/0002/000178 data/0002/000179 data/0002/000180 data/0002/000181 data/0002/000182 data/0002/000183 data/0002/000184 data/0002/000185 data/0002/000186 data/0002/000187 data/0002/000188 data/0002/000189 data/0002/000190 data/0002/000191 data/0002/000192 data/0002/000193 data/0002/000194 data/0002/000195 data/0002/000196 data/0002/000197 data/0002/000198 data/0002/000199 data/0002/000200 data/0002/000201 data/0002/000202 data/0002/000203 data/0002/000204 data/0002/000205 data/0002/000206 data/0002/000207 data/0002/000208 data/0002/000209 data/0002/000210 data/0002/000211 data/0002/000212 data/0002/000213 data/0002/000214 data/0002/000215 data/0002/000216 data/0002/000217 data/0002/000218 data/0002/000219 data/0002/000220 data/0002/000221 data/0002/000222 data/0002/000223 data/0002/000224 data/0002/000225 data/0002/000226 data/0002/000227 data/0002/000228 data/0002/000229 data/0002/000230 data/0002/000231 data/0002/000232 data/0002/000233 data/0002/000234 data/0002/000235 data/0002/000236 data/0002/000237 data/0002/000238 data/0002/000239 data/0002/000240 data/0002/000241 data/0002/000242 data/0002/000243 data/0002/000244 data/0002/000245 data/0002/000246 data/0002/000247 data/0002/000248 data/0002/000249 data/0002/000250 data/0002/000251 data/0002/000252 data/0002/000253 data/0002/000254 data/0002/000255 data/0002/000256 data/0002/000257 data/0002/000258 data/0002/000259 data/0002/000260 data/0002/000261 data/0002/000262 data/0002/000263 data/0002/000264 data/0002/000265 data/0002/000266 data/0002/000267 data/0002/000268 data/0002/000269 data/0002/000270 data/0002/000271 data/0002/000272 data/0002/000273 data/0002/000274 data/0002/000275 data/0002/000276 data/0002/000277 data/0002/000278 data/0002/000279 data/0002/000280 data/0002/000281 data/0002/000282 data/0002/000283 data/0002/000284 data/0002/000285 data/0002/000286 data/0002/000287 data/0002/000288 data/0002/000289 data/0002/000290 data/0002/000291 data/0002/000292 data/0002/000293 data/0002/000294 data/0002/000295 data/0002/000296 data/0002/000297 data/0002/000298 data/0002/000299 data/0002/000300 data/0002/000301 data/0002/000302 data/0002/000303 data/0002/000304 data/0002/000305 data/0002/000306 data/0002/000307 data/0002/000308 data/0002/000309 data/0002/000310 data/0002/000311 data/0002/000312 data/0002/000313 data/0002/000314 data/0002/000315 data/0002/000316 data/0002/000317 data/0002/000318 data/0002/000319 data/0002/000320 data/0002/000321 data/0002/000322 data/0002/000323 data/0002/000324 data/0002/000325 data/0002/000326 data/0002/000327 data/0002/000328 data/0002/000329 data/0002/000330 data/0002/000331 data/0002/000332 data/0002/000333 data/0002/000334 data/0002/000335 data/0002/000336 data/0002/000337 data/0002/000338 data/0002/000339 data/0002/000340 data/0002/000341 data/0002/000342 data/0002/000343 data/0002/000344 data/0002/000345 data/0002/000346 data/0002/000347 data/0002/000348 data/0002/000349 data/0002/000350 data/0002/000351 data/0002/000352 data/0002/000353 data/0002/000354 data/0002/000355 data/0002/000356 data/0002/000357 data/0002/000358 data/0002/000359 data/0002/000360 data/0002/000361 data/0002/000362 data/0002/000363 data/0002/000364 data/0002/000365 data/0002/000366 data/0002/000367 data/0002/000368 data/0002/000369 data/0002/000370 data/0002/000371 data/0002/000372 data/0002/000373 data/0002/000374 data/0002/000375 data/0002/000376 data/0002/000377 data/0002/000378 data/0002/000379 data/0002/000380 data/0002/000381 data/0002/000382 data/0002/000383 data/0002/000384 data/0002/000385 data/0002/000386 data/0002/000387 data/0002/000388 data/0002/000389 data/0002/000390 data/0002/000391 data/0002/000392 data/0002/000393 data/0002/000394 data/0002/000395 data/0002/000396 data/0002/000397 data/0002/000398 data/0002/000399 data/0002/000400 data/0002/000401 data/0002/000402 data/0002/000403 data/0002/000404 data/0002/000405 data/0002/000406 data/0002/000407 data/0002/000408 data/0002/000409 data/0002/000410 data/0002/000411 data/0002/000412 data/0002/000413 data/0002/000414 data/0002/000415 data/0002/000416 data/0002/000417 data/0002/000418 data/0002/000419 data/0002/000420 data/0002/000421 data/0002/000422 data/0002/000423 data/0002/000424 data/0002/000425 data/0002/000426 data/0002/000427 data/0002/000428 data/0002/000429 data/0002/000430 data/0002/000431 data/0002/000432 data/0002/000433 data/0002/000434 data/0002/000435 data/0002/000436 data/0002/000437 data/0002/000438 data/0002/000439 data/0002/000440 data/0002/000441 data/0002/000442 data/0002/000443 data/0002/000444 data/0002/000445 data/0002/000446 data/0002/000447 data/0002/000448 data/0002/000449 data/0002/000450 data/0002/000451 data/0002/000452 data/0002/000453 data/0002/000454 data/0002/000455 data/0002/000456 data/0002/000457 data/0002/000458 data/0002/000459 data/0002/000460 data/0002/000461 data/0002/000462 data/0002/000463 data/0002/000464 data/0002/000465 data/0002/000466 data/0002/000467 data/0002/000468 data/0002/000469 data/0002/000470 data/0002/000471 data/0002/000472 data/0002/000473 data/0002/000474 data/0002/000475 data/0002/000476 data/0002/000477 data/0002/000478 data/0002/000479 data/0002/000480 data/0002/000481 data/0002/000482 data/0002/000483 data/0002/000484 data/0002/000485 data/0002/000486 data/0002/000487 data/0002/000488 data/0002/000489 data/0002/000490 data/0002/000491 data/0002/000492 data/0002/000493 data/0002/000494 data/0002/000495 data/0002/000496 data/0002/000497 data/0002/000498 data/0002/000499 data/0002/000500 data/0002/000501 data/0002/000502 data/0002/000503 data/0002/000504 data/0002/000505 data/0002/000506 data/0002/000507 data/0002/000508 data/0002/000509 data/0002/000510 data/0002/000511 data/0002/000512 data/0002/000513 data/0002/000514 data/0002/000515 data/0002/000516 data/0002/000517 data/0002/000518 data/0002/000519 data/0002/000520 data/0002/000521 data/0002/000522 data/0002/000523 data/0002/000524 data/0002/000525 data/0002/000526 data/0002/000527 data/0002/000528 data/0002/000529 data/0002/000530 data/0002/000531 data/0002/000532 data/0002/000533 data/0002/000534 data/0002/000535 data/0002/000536 data/0002/000537 data/0002/000538 data/0002/000539 data/0002/000540 data/0002/000541 data/0002/000542 data/0002/000543 data/0002/000544 data/0002/000545 data/0002/000546 data/0002/000547 data/0002/000548 data/0002/000549 data/0002/000550 data/0002/000551 data/0002/000552 data/0002/000553 data/0002/000554 data/0002/000555 data/0002/000556 data/0002/000557 data/0002/000558 data/0002/000559 data/0002/000560 data/0002/000561 data/0002/000562 data/0002/000563 data/0002/000564 data/0002/000565 data/0002/000566 data/0002/000567 data/0002/000568 data/0002/000569 data/0002/000570 data/0002/000571 data/0002/000572 data/0002/000573 data/0002/000574 data/0002/000575 data/0002/000576 data/0002/000577 data/0002/000578 data/0002/000579 data/0002/000580 data/0002/000581 data/0002/000582 data/0002/000583 data/0002/000584 data/0002/000585 data/0002/000586 data/0002/000587 data/0002/000588 data/0002/000589 data/0002/000590 data/0002/000591 data/0002/000592 data/0002/000593 data/0002/000594 data/0002/000595 data/0002/000596 data/0002/000597 data/0002/000598 data/0002/000599 data/0002/000600 data/0002/000601 data/0002/000602 data/0002/000603 data/0002/000604 data/0002/000605 data/0002/000606 data/0002/000607 data/0002/000608 data/0002/000609 data/0002/000610 data/0002/000611 data/0002/000612 data/0002/000613 data/0002/000614 data/0002/000615 data/0002/000616 data/0002/000617 data/0002/000618 data/0002/000619 data/0002/000620 data/0002/000621 data/0002/000622 data/0002/000623 data/0002/000624 data/0002/000625 data/0002/000626 data/0002/000627 data/0002/000628 data/0002/000629 data/0002/000630 data/0002/000631 data/0002/000632 data/0002/000633 data/0002/000634 data/0002/000635 data/0002/000636 data/0002/000637 data/0002/000638 data/0002/000639 data/0002/000640 data/0002/000641 data/0002/000642 data/0002/000643 data/0002/000644 data/0002/000645 data/0002/000646 data/0002/000647 data/0002/000648 data/0002/000649 data/0002/000650 data/0002/000651 data/0002/000652 data/0002/000653 data/0002/000654 data/0002/000655 data/0002/000656 data/0002/000657 data/0002/000658 data/0002/000659 data/0002/000660 data/0002/000661 data/0002/000662 data/0002/000663 data/0002/000664 data/0002/000665 data/0002/000666 data/0002/000667 data/0002/000668 data/0002/000669 data/0002/000670 data/0002/000671 data/0002/000672 data/0002/000673 data/0002/000674 data/0002/000675 data/0002/000676 data/0002/000677 data/0002/000678 data/0002/000679 data/0002/000680 data/0002/000681 data/0002/000682 data/0002/000683 data/0002/000684 data/0002/000685 data/0002/000686 data/0002/000687 data/0002/000688 data/0002/000689 data/0002/000690 data/0002/000691 data/0002/000692 data/0002/000693 data/0002/000694 data/0002/000695 data/0002/000696 data/0002/000697 data/0002/000698 data/0002/000699 data/0002/000700 data/0002/000701 data/0002/000702 data/0002/000703 data/0002/000704 data/0002/000705 data/0002/000706 data/0002/000707 data/0002/000708 data/0002/000709 data/0002/000710 data/0002/000711 data/0002/000712 data/0002/000713 data/0002/000714 data/0002/000715 data/0002/000716 data/0002/000717 data/0002/000718 data/0002/000719 data/0002/000720 data/0002/000721 data/0002/000722 data/0002/000723 data/0002/000724 data/0002/000725 data/0002/000726 data/0002/000727 data/0002/000728 data/0002/000729 data/0002/000730 data/0002/000731 data/0002/000732 data/0002/000733 data/0002/000734 data/0002/000735 data/0002/000736 data/0002/000737 data/0002/000738 data/0002/000739 data/0002/000740 data/0002/000741 data/0002/000742 data/0002/000743 data/0002/000744 data/0002/000745 data/0002/000746 data/0002/000747 data/0002/000748 data/0002/000749 data/0002/000750 data/0002/000751 data/0002/000752 data/0002/000753 data/0002/000754 data/0002/000755 data/0002/000756 data/0002/000757 data/0002/000758 data/0002/000759 data/0002/000760 data/0002/000761 data/0002/000762 data/0002/000763 data/0002/000764 data/0002/000765 data/0002/000766 data/0002/000767 data/0002/000768 data/0002/000769 data/0002/000770 data/0002/000771 data/0002/000772 data/0002/000773 data/0002/000774 data/0002/000775 data/0002/000776 data/0002/000777 data/0002/000778 data/0002/000779 data/0002/000780 data/0002/000781 data/0002/000782 data/0002/000783 data/0002/000784 data/0002/000785 data/0002/000786 data/0002/000787 data/0002/000788 data/0002/000789 data/0002/000790 data/0002/000791 data/0002/000792 data/0002/000793 data/0002/000794 data/0002/000795 data/0002/000796 data/0002/000797 data/0002/000798 data/0002/000799 data/0002/000800 data/0002/000801 data/0002/000802 data/0002/000803 data/0002/000804 data/0002/000805 data/0002/000806 data/0002/000807 data/0002/000808 data/0002/000809 data/0002/000810 data/0002/000811 data/0002/000812 data/0002/000813 data/0002/000814 data/0002/000815 data/0002/000816 data/0002/000817 data/0002/000818 data/0002/000819 data/0002/000820 data/0002/000821 data/0002/000822 data/0002/000823 data/0002/000824 data/0002/000825 data/0002/000826 data/0002/000827 data/0002/000828 data/0002/000829 data/0002/000830 data/0002/000831 data/0002/000832 data/0002/000833 data/0002/000834 data/0002/000835 data/0002/000836 data/0002/000837 data/0002/000838 data/0002/000839 data/0002/000840 data/0002/000841 data/0002/000842 data/0002/000843 data/0002/000844 data/0002/000845 data/0002/000846 data/0002/000847 data/0002/000848 data/0002/000849 data/0002/000850 data/0002/000851 data/0002/000852 data/0002/000853 data/0002/000854 data/0002/000855 data/0002/000856 data/0002/000857 data/0002/000858 data/0002/000859 data/0002/000860 data/0002/000861 data/0002/000862 data/0002/000863 data/0002/000864 data/0002/000865 data/0002/000866 data/0002/000867 data/0002/000868 data/0002/000869 data/0002/000870 data/0002/000871 data/0002/000872 data/0002/000873 data/0002/000874 data/0002/000875 data/0002/000876 data/0002/000877 data/0002/000878 data/0002/000879 data/0002/000880 data/0002/000881 data/0002/000882 data/0002/000883 data/0002/000884 data/0002/000885 data/0002/000886 data/0002/000887 data/0002/000888 data/0002/000889 data/0002/000890 data/0002/000891 data/0002/000892 data/0002/000893 data/0002/000894 data/0002/000895 data/0002/000896 data/0002/000897 data/0002/000898 data/0002/000899 data/0002/000900 data/0002/000901 data/0002/000902 data/0002/000903 data/0002/000904 data/0002/000905 data/0002/000906 data/0002/000907 data/0002/000908 data/0002/000909 data/0002/000910 data/0002/000911 data/0002/000912 data/0002/000913 data/0002/000914 data/0002/000915 data/0002/000916 data/0002/000917 data/0002/000918 data/0002/000919 data/0002/000920 data/0002/000921 data/0002/000922 data/0002/000923 data/0002/000924 data/0002/000925 data/0002/000926 data/0002/000927 data/0002/000928 data/0002/000929 data/0002/000930 data/0002/000931 data/0002/000932 data/0002/000933 data/0002/000934 data/0002/000935 data/0002/000936 data/0002/000937 data/0002/000938 data/0002/000939 data/0002/000940 data/0002/000941 data/0002/000942 data/0002/000943 data/0002/000944 data/0002/000945 data/0002/000946 data/0002/000947 data/0002/000948 data/0002/000949 data/0002/000950 data/0002/000951 data/0002/000952 data/0002/000953 data/0002/000954 data/0002/000955 data/0002/000956 data/0002/000957 data/0002/000958 data/0002/000959 data/0002/000960 data/0002/000961 data/0002/000962 data/0002/000963 data/0002/000964 data/0002/000965 data/0002/000966 data/0002/000967 data/0002/000968 data/0002/000969 data/0002/000970 data/0002/000971 data/0002/000972 data/0002/000973 data/0002/000974 data/0002/000975 data/0002/000976 data/0002/000977 data/0002/000978 data/0002/000979 data/0002/000980 data/0002/000981 data/0002/000982 data/0002/000983 data/0002/000984 data/0002/000985 data/0002/000986 data/0002/000987 data/0002/000988 data/0002/000989 data/0002/000990 data/0002/000991 data/0002/000992 data/0002/000993 data/0002/000994 data/0002/000995 data/0002/000996 data/0002/000997 data/0002/000998 data/0002/000999 data/0002/001000 data/0002/001001 data/0002/001002 data/0002/001003 data/0002/001004 data/0002/001005 data/0002/001006 data/0002/001007 data/0002/001008 data/0002/001009 data/0002/001010 data/0002/001011 data/0002/001012 data/0002/001013 data/0002/001014 data/0002/001015 data/0002/001016 data/0002/001017 data/0002/001018 data/0002/001019 data/0002/001020 data/0002/001021 data/0002/001022 data/0002/001023 data/0002/001024 data/0002/001025 data/0002/001026 data/0002/001027 data/0002/001028 data/0002/001029 data/0002/001030 data/0002/001031 data/0002/001032 data/0002/001033 data/0002/001034 data/0002/001035 data/0002/001036 data/0002/001037 data/0002/001038 data/0002/001039 data/0002/001040 data/0002/001041 data/0002/001042 data/0002/001043 data/0002/001044 data/0002/001045 data/0002/001046 data/0002/001047 data/0002/001048 data/0002/001049 data/0002/001050 data/0002/001051 data/0002/001052 data/0002/001053 data/0002/001054 data/0002/001055 data/0002/001056 data/0002/001057 data/0002/001058 data/0002/001059 data/0002/001060 data/0002/001061 data/0002/001062 data/0002/001063 data/0002/001064 data/0002/001065 data/0002/001066 data/0002/001067 data/0002/001068 data/0002/001069 data/0002/001070 data/0002/001071 data/0002/001072 data/0002/001073 data/0002/001074 data/0002/001075 data/0002/001076 data/0002/001077 data/0002/001078 data/0002/001079 data/0002/001080 data/0002/001081 data/0002/001082 data/0002/001083 data/0002/001084 data/0002/001085 data/0002/001086 data/0002/001087 data/0002/001088 data/0002/001089 data/0002/001090 data/0002/001091 data/0002/001092 data/0002/001093 data/0002/001094 data/0002/001095 data/0002/001096 data/0002/001097 data/0002/001098 data/0002/001099 data/0002/001100 data/0002/001101 data/0002/001102 data/0002/001103 data/0002/001104 data/0002/001105 data/0002/001106 data/0002/001107 data/0002/001108 data/0002/001109 data/0002/001110 data/0002/001111 data/0002/001112 data/0002/001113 data/0002/001114 data/0002/001115 data/0002/001116 data/0002/001117 data/0002/001118 data/0002/001119 data/0002/001120 data/0002/001121 data/0002/001122 data/0002/001123 data/0002/001124 data/0002/001125 data/0002/001126 data/0002/001127 data/0002/001128 data/0002/001129 data/0002/001130 data/0002/001131 data/0002/001132 data/0002/001133 data/0002/001134 data/0002/001135 data/0002/001136 data/0002/001137 data/0002/001138 data/0002/001139 data/0002/001140 data/0002/001141 data/0002/001142 data/0002/001143 data/0002/001144 data/0002/001145 data/0002/001146 data/0002/001147 data/0002/001148 data/0002/001149 data/0002/001150 data/0002/001151 data/0002/001152 data/0002/001153 data/0002/001154 data/0002/001155 data/0002/001156 data/0002/001157 data/0002/001158 data/0002/001159 data/0002/001160 data/0002/001161 data/0002/001162 data/0002/001163 data/0002/001164 data/0002/001165 data/0002/001166 data/0002/001167 data/0002/001168 data/0002/001169 data/0002/001170 data/0002/001171 data/0002/001172 data/0002/001173 data/0002/001174 data/0002/001175 data/0002/001176 data/0002/001177 data/0002/001178 data/0002/001179 data/0002/001180 data/0002/001181 data/0002/001182 data/0002/001183 data/0002/001184 data/0002/001185 data/0002/001186 data/0002/001187 data/0002/001188 data/0002/001189 data/0002/001190 data/0002/001191 data/0002/001192 data/0002/001193 data/0002/001194 data/0002/001195 data/0002/001196 data/0002/001197 data/0002/001198 data/0002/001199 data/0002/001200 data/0002/001201 data/0002/001202 data/0002/001203 data/0002/001204 data/0002/001205 data/0002/001206 data/0002/001207 data/0002/001208 data/0002/001209 data/0002/001210 data/0002/001211 data/0002/001212 data/0002/001213 data/0002/001214 data/0002/001215 data/0002/001216 data/0002/001217 data/0002/001218 data/0002/001219 data/0002/001220 data/0002/001221 data/0002/001222 data/0002/001223 data/0002/001224 data/0002/001225 data/0002/001226 data/0002/001227 data/0002/001228 data/0002/001229 data/0002/001230 data/0002/001231 data/0002/001232 data/0002/001233 data/0002/001234 data/0002/001235 data/0002/001236 data/0002/001237 data/0002/001238 data/0002/001239 data/0002/001240 data/0002/001241 data/0002/001242 data/0002/001243 data/0002/001244 data/0002/001245 data/0002/001246 data/0002/001247 data/0002/001248 data/0002/001249 data/0002/001250 data/0002/001251 data/0002/001252 data/0002/001253 data/0002/001254 data/0002/001255 data/0002/001256 data/0002/001257 data/0002/001258 data/0002/001259 data/0002/001260 data/0002/001261 data/0002/001262 data/0004/000001 data/0004/000002 data/0004/000003 data/0004/000004 data/0004/000005 data/0004/000006 data/0004/000007 data/0004/000008 data/0004/000009 data/0004/000010 data/0004/000011 data/0004/000012 data/0004/000013 data/0004/000014 data/0004/000015 data/0004/000016 data/0004/000017 data/0004/000018 data/0004/000019 data/0004/000020 data/0004/000021 data/0004/000022 data/0004/000023 data/0004/000024 data/0004/000025 data/0004/000026 data/0004/000027 data/0004/000028 data/0004/000029 data/0004/000030 data/0004/000031 data/0004/000032 data/0004/000033 data/0004/000034 data/0004/000035 data/0004/000036 data/0004/000037 data/0004/000038 data/0004/000039 data/0004/000040 data/0004/000041 data/0004/000042 data/0004/000043 data/0004/000044 data/0004/000045 data/0004/000046 data/0004/000047 data/0004/000048 data/0004/000049 data/0004/000050 data/0004/000051 data/0004/000052 data/0004/000053 data/0004/000054 data/0004/000055 data/0004/000056 data/0004/000057 data/0004/000058 data/0004/000059 data/0004/000060 data/0004/000061 data/0004/000062 data/0004/000063 data/0004/000064 data/0004/000065 data/0004/000066 data/0004/000067 data/0004/000068 data/0004/000069 data/0004/000070 data/0004/000071 data/0004/000072 data/0004/000073 data/0004/000074 data/0004/000075 data/0004/000076 data/0004/000077 data/0004/000078 data/0004/000079 data/0004/000080 data/0004/000081 data/0004/000082 data/0004/000083 data/0004/000084 data/0004/000085 data/0004/000086 data/0004/000087 data/0004/000088 data/0004/000089 data/0004/000090 data/0004/000091 data/0004/000092 data/0004/000093 data/0004/000094 data/0004/000095 data/0004/000096 data/0004/000097 data/0004/000098 data/0004/000099 data/0004/000100 data/0004/000101 data/0004/000102 data/0004/000103 data/0004/000104 data/0004/000105 data/0004/000106 data/0004/000107 data/0004/000108 data/0004/000109 data/0004/000110 data/0004/000111 data/0004/000112 data/0004/000113 data/0004/000114 data/0004/000115 data/0004/000116 data/0004/000117 data/0004/000118 data/0004/000119 data/0004/000120 data/0004/000121 data/0004/000122 data/0004/000123 data/0004/000124 data/0004/000125 data/0004/000126 data/0004/000127 data/0004/000128 data/0004/000129 data/0004/000130 data/0004/000131 data/0004/000132 data/0004/000133 data/0004/000134 data/0004/000135 data/0004/000136 data/0004/000137 data/0004/000138 data/0004/000139 data/0004/000140 data/0004/000141 data/0004/000142 data/0004/000143 data/0004/000144 data/0004/000145 data/0004/000146 data/0004/000147 data/0004/000148 data/0004/000149 data/0004/000150 data/0004/000151 data/0004/000152 data/0004/000153 data/0004/000154 data/0004/000155 data/0004/000156 data/0004/000157 data/0004/000158 data/0004/000159 data/0004/000160 data/0004/000161 data/0004/000162 data/0004/000163 data/0004/000164 data/0004/000165 data/0004/000166 data/0004/000167 data/0004/000168 data/0004/000169 data/0004/000170 data/0004/000171 data/0004/000172 data/0004/000173 data/0004/000174 data/0004/000175 data/0004/000176 data/0004/000177 data/0004/000178 data/0004/000179 data/0004/000180 data/0004/000181 data/0004/000182 data/0004/000183 data/0004/000184 data/0004/000185 data/0004/000186 data/0004/000187 data/0004/000188 data/0004/000189 data/0004/000190 data/0004/000191 data/0004/000192 data/0004/000193 data/0004/000194 data/0004/000195 data/0004/000196 data/0004/000197 data/0004/000198 data/0004/000199 data/0004/000200 data/0004/000201 data/0004/000202 data/0004/000203 data/0004/000204 data/0004/000205 data/0004/000206 data/0004/000207 data/0004/000208 data/0004/000209 data/0004/000210 data/0004/000211 data/0004/000212 data/0004/000213 data/0004/000214 data/0004/000215 data/0004/000216 data/0004/000217 data/0004/000218 data/0004/000219 data/0004/000220 data/0004/000221 data/0004/000222 data/0004/000223 data/0004/000224 data/0004/000225 data/0004/000226 data/0004/000227 data/0004/000228 data/0004/000229 data/0004/000230 data/0004/000231 data/0004/000232 data/0004/000233 data/0004/000234 data/0004/000235 data/0004/000236 data/0004/000237 data/0004/000238 data/0004/000239 data/0004/000240 data/0004/000241 data/0004/000242 data/0004/000243 data/0004/000244 data/0004/000245 data/0004/000246 data/0004/000247 data/0004/000248 data/0004/000249 data/0004/000250 data/0004/000251 data/0004/000252 data/0004/000253 data/0004/000254 data/0004/000255 data/0004/000256 data/0004/000257 data/0004/000258 data/0004/000259 data/0004/000260 data/0004/000261 data/0004/000262 data/0004/000263 data/0004/000264 data/0004/000265 data/0004/000266 data/0004/000267 data/0004/000268 data/0004/000269 data/0004/000270 data/0004/000271 data/0004/000272 data/0004/000273 data/0004/000274 data/0004/000275 data/0004/000276 data/0004/000277 data/0004/000278 data/0004/000279 data/0004/000280 data/0004/000281 data/0004/000282 data/0004/000283 data/0004/000284 data/0004/000285 data/0004/000286 data/0004/000287 data/0004/000288 data/0004/000289 data/0004/000290 data/0004/000291 data/0004/000292 data/0004/000293 data/0004/000294 data/0004/000295 data/0004/000296 data/0004/000297 data/0004/000298 data/0004/000299 data/0004/000300 data/0004/000301 data/0004/000302 data/0004/000303 data/0004/000304 data/0004/000305 data/0004/000306 data/0004/000307 data/0004/000308 data/0004/000309 data/0004/000310 data/0004/000311 data/0004/000312 data/0004/000313 data/0004/000314 data/0004/000315 data/0004/000316 data/0004/000317 data/0004/000318 data/0004/000319 data/0004/000320 data/0004/000321 data/0004/000322 data/0004/000323 data/0004/000324 data/0004/000325 data/0004/000326 data/0004/000327 data/0004/000328 data/0004/000329 data/0004/000330 data/0004/000331 data/0004/000332 data/0004/000333 data/0004/000334 data/0004/000335 data/0004/000336 data/0004/000337 data/0004/000338 data/0004/000339 data/0004/000340 data/0004/000341 data/0004/000342 data/0004/000343 data/0004/000344 data/0004/000345 data/0004/000346 data/0004/000347 data/0004/000348 data/0004/000349 data/0004/000350 data/0004/000351 data/0004/000352 data/0004/000353 data/0004/000354 data/0004/000355 data/0004/000356 data/0004/000357 data/0004/000358 data/0004/000359 data/0004/000360 data/0004/000361 data/0004/000362 data/0004/000363 data/0004/000364 data/0004/000365 data/0004/000366 data/0004/000367 data/0004/000368 data/0004/000369 data/0004/000370 data/0004/000371 data/0004/000372 data/0004/000373 data/0004/000374 data/0004/000375 data/0004/000376 data/0004/000377 data/0004/000378 data/0004/000379 data/0004/000380 data/0004/000381 data/0004/000382 data/0004/000383 data/0004/000384 data/0004/000385 data/0004/000386 data/0004/000387 data/0004/000388 data/0004/000389 data/0004/000390 data/0004/000391 data/0004/000392 data/0004/000393 data/0004/000394 data/0004/000395 data/0004/000396 data/0004/000397 data/0004/000398 data/0004/000399 data/0004/000400 data/0004/000401 data/0004/000402 data/0004/000403 data/0004/000404 data/0004/000405 data/0004/000406 data/0004/000407 data/0004/000408 data/0004/000409 data/0004/000410 data/0004/000411 data/0004/000412 data/0004/000413 data/0004/000414 data/0004/000415 data/0004/000416 data/0004/000417 data/0004/000418 data/0004/000419 data/0004/000420 data/0004/000421 data/0004/000422 data/0004/000423 data/0004/000424 data/0004/000425 data/0004/000426 data/0004/000427 data/0004/000428 data/0004/000429 data/0004/000430 data/0004/000431 data/0004/000432 data/0004/000433 data/0004/000434 data/0004/000435 data/0004/000436 data/0004/000437 data/0004/000438 data/0004/000439 data/0004/000440 data/0004/000441 data/0004/000442 data/0004/000443 data/0004/000444 data/0004/000445 data/0004/000446 data/0004/000447 data/0004/000448 data/0004/000449 data/0004/000450 data/0004/000451 data/0004/000452 data/0004/000453 data/0004/000454 data/0004/000455 data/0004/000456 data/0004/000457 data/0004/000458 data/0004/000459 data/0004/000460 data/0004/000461 data/0004/000462 data/0004/000463 data/0004/000464 data/0004/000465 data/0004/000466 data/0004/000467 data/0004/000468 data/0004/000469 data/0004/000470 data/0004/000471 data/0004/000472 data/0004/000473 data/0004/000474 data/0004/000475 data/0004/000476 data/0004/000477 data/0004/000478 data/0004/000479 data/0004/000480 data/0004/000481 data/0004/000482 data/0004/000483 data/0004/000484 data/0004/000485 data/0004/000486 data/0004/000487 data/0004/000488 data/0004/000489 data/0004/000490 data/0004/000491 data/0004/000492 data/0004/000493 data/0004/000494 data/0004/000495 data/0004/000496 data/0004/000497 data/0004/000498 data/0004/000499 data/0004/000500 data/0004/000501 data/0004/000502 data/0004/000503 data/0004/000504 data/0004/000505 data/0004/000506 data/0004/000507 data/0004/000508 data/0004/000509 data/0004/000510 data/0004/000511 data/0004/000512 data/0004/000513 data/0004/000514 data/0004/000515 data/0004/000516 data/0004/000517 data/0004/000518 data/0004/000519 data/0004/000520 data/0004/000521 data/0004/000522 data/0004/000523 data/0004/000524 data/0004/000525 data/0004/000526 data/0004/000527 data/0004/000528 data/0004/000529 data/0004/000530 data/0004/000531 data/0004/000532 data/0004/000533 data/0004/000534 data/0004/000535 data/0004/000536 data/0004/000537 data/0004/000538 data/0004/000539 data/0004/000540 data/0004/000541 data/0004/000542 data/0004/000543 data/0004/000544 data/0004/000545 data/0004/000546 data/0004/000547 data/0004/000548 data/0004/000549 data/0004/000550 data/0004/000551 data/0004/000552 data/0004/000553 data/0004/000554 data/0004/000555 data/0004/000556 data/0004/000557 data/0004/000558 data/0004/000559 data/0004/000560 data/0004/000561 data/0004/000562 data/0004/000563 data/0004/000564 data/0004/000565 data/0004/000566 data/0004/000567 data/0004/000568 data/0004/000569 data/0004/000570 data/0004/000571 data/0004/000572 data/0004/000573 data/0004/000574 data/0004/000575 data/0004/000576 data/0004/000577 data/0004/000578 data/0004/000579 data/0004/000580 data/0004/000581 data/0004/000582 data/0004/000583 data/0004/000584 data/0004/000585 data/0004/000586 data/0004/000587 data/0004/000588 data/0004/000589 data/0004/000590 data/0004/000591 data/0004/000592 data/0004/000593 data/0004/000594 data/0004/000595 data/0004/000596 data/0004/000597 data/0004/000598 data/0004/000599 data/0004/000600 data/0004/000601 data/0004/000602 data/0004/000603 data/0005/000001 data/0005/000002 data/0005/000003 data/0005/000004 data/0005/000005 data/0005/000006 data/0005/000007 data/0005/000008 data/0005/000009 data/0005/000010 data/0005/000011 data/0005/000012 data/0005/000013 data/0005/000014 data/0005/000015 data/0005/000016 data/0005/000017 data/0005/000018 data/0005/000019 data/0005/000020 data/0005/000021 data/0005/000022 data/0005/000023 data/0005/000024 data/0005/000025 data/0005/000026 data/0005/000027 data/0005/000028 data/0005/000029 data/0005/000030 data/0005/000031 data/0005/000032 data/0005/000033 data/0005/000034 data/0005/000035 data/0005/000036 data/0005/000037 data/0005/000038 data/0005/000039 data/0005/000040 data/0005/000041 data/0005/000042 data/0005/000043 data/0005/000044 data/0005/000045 data/0005/000046 data/0005/000047 data/0005/000048 data/0005/000049 data/0005/000050 data/0005/000051 data/0005/000052 data/0005/000053 data/0005/000054 data/0005/000055 data/0005/000056 data/0005/000057 data/0005/000058 data/0005/000059 data/0005/000060 data/0005/000061 data/0005/000062 data/0005/000063 data/0005/000064 data/0005/000065 data/0005/000066 data/0005/000067 data/0005/000068 data/0005/000069 data/0005/000070 data/0005/000071 data/0005/000072 data/0005/000073 data/0005/000074 data/0005/000075 data/0005/000076 data/0005/000077 data/0005/000078 data/0005/000079 data/0005/000080 data/0005/000081 data/0005/000082 data/0005/000083 data/0005/000084 data/0005/000085 data/0005/000086 data/0005/000087 data/0005/000088 data/0005/000089 data/0005/000090 data/0005/000091 data/0005/000092 data/0005/000093 data/0005/000094 data/0005/000095 data/0005/000096 data/0005/000097 data/0005/000098 data/0005/000099 data/0005/000100 data/0005/000101 data/0005/000102 data/0005/000103 data/0005/000104 data/0005/000105 data/0005/000106 data/0005/000107 data/0005/000108 data/0005/000109 data/0005/000110 data/0005/000111 data/0005/000112 data/0005/000113 data/0005/000114 data/0005/000115 data/0005/000116 data/0005/000117 data/0005/000118 data/0005/000119 data/0005/000120 data/0005/000121 data/0005/000122 data/0005/000123 data/0005/000124 data/0005/000125 data/0005/000126 data/0005/000127 data/0005/000128 data/0005/000129 data/0005/000130 data/0005/000131 data/0005/000132 data/0005/000133 data/0005/000134 data/0005/000135 data/0005/000136 data/0005/000137 data/0005/000138 data/0005/000139 data/0005/000140 data/0005/000141 data/0005/000142 data/0005/000143 data/0005/000144 data/0005/000145 data/0005/000146 data/0005/000147 data/0005/000148 data/0005/000149 data/0005/000150 data/0005/000151 data/0005/000152 data/0005/000153 data/0005/000154 data/0005/000155 data/0005/000156 data/0005/000157 data/0005/000158 data/0005/000159 data/0005/000160 data/0005/000161 data/0005/000162 data/0005/000163 data/0005/000164 data/0005/000165 data/0005/000166 data/0005/000167 data/0005/000168 data/0005/000169 data/0005/000170 data/0005/000171 data/0005/000172 data/0005/000173 data/0005/000174 data/0005/000175 data/0005/000176 data/0005/000177 data/0005/000178 data/0005/000179 data/0005/000180 data/0005/000181 data/0005/000182 data/0005/000183 data/0005/000184 data/0005/000185 data/0005/000186 data/0005/000187 data/0005/000188 data/0005/000189 data/0005/000190 data/0005/000191 data/0005/000192 data/0005/000193 data/0005/000194 data/0005/000195 data/0005/000196 data/0005/000197 data/0005/000198 data/0005/000199 data/0005/000200 data/0005/000201 data/0005/000202 data/0005/000203 data/0005/000204 data/0005/000205 data/0005/000206 data/0005/000207 data/0005/000208 data/0005/000209 data/0005/000210 data/0005/000211 data/0005/000212 data/0005/000213 data/0005/000214 data/0005/000215 data/0005/000216 data/0005/000217 data/0005/000218 data/0005/000219 data/0005/000220 data/0005/000221 data/0005/000222 data/0005/000223 data/0005/000224 data/0005/000225 data/0005/000226 data/0005/000227 data/0005/000228 data/0005/000229 data/0005/000230 data/0005/000231 data/0005/000232 data/0005/000233 data/0005/000234 data/0005/000235 data/0005/000236 data/0005/000237 data/0005/000238 data/0005/000239 data/0005/000240 data/0005/000241 data/0005/000242 data/0005/000243 data/0005/000244 data/0005/000245 data/0005/000246 data/0005/000247 data/0005/000248 data/0005/000249 data/0005/000250 data/0005/000251 data/0005/000252 data/0005/000253 data/0005/000254 data/0005/000255 data/0005/000256 data/0005/000257 data/0005/000258 data/0005/000259 data/0005/000260 data/0005/000261 data/0005/000262 data/0005/000263 data/0005/000264 data/0005/000265 data/0005/000266 data/0005/000267 data/0005/000268 data/0005/000269 data/0005/000270 data/0005/000271 data/0005/000272 data/0005/000273 data/0005/000274 data/0005/000275 data/0005/000276 data/0005/000277 data/0005/000278 data/0005/000279 data/0005/000280 data/0005/000281 data/0005/000282 data/0005/000283 data/0005/000284 data/0005/000285 data/0005/000286 data/0005/000287 data/0005/000288 data/0005/000289 data/0005/000290 data/0005/000291 data/0005/000292 data/0005/000293 data/0005/000294 data/0005/000295 data/0005/000296 data/0005/000297 data/0005/000298 data/0005/000299 data/0005/000300 data/0005/000301 data/0005/000302 data/0005/000303 data/0005/000304 data/0005/000305 data/0005/000306 data/0005/000307 data/0005/000308 data/0005/000309 data/0005/000310 data/0005/000311 data/0005/000312 data/0005/000313 data/0005/000314 data/0005/000315 data/0005/000316 data/0005/000317 data/0005/000318 data/0005/000319 data/0005/000320 data/0005/000321 data/0005/000322 data/0005/000323 data/0005/000324 data/0005/000325 data/0005/000326 data/0005/000327 data/0005/000328 data/0005/000329 data/0005/000330 data/0005/000331 data/0005/000332 data/0005/000333 data/0005/000334 data/0005/000335 data/0005/000336 data/0005/000337 data/0005/000338 data/0005/000339 data/0005/000340 data/0005/000341 data/0005/000342 data/0005/000343 data/0005/000344 data/0005/000345 data/0005/000346 data/0005/000347 data/0005/000348 data/0005/000349 data/0005/000350 data/0005/000351 data/0005/000352 data/0005/000353 data/0005/000354 data/0005/000355 data/0005/000356 data/0005/000357 data/0005/000358 data/0005/000359 data/0005/000360 data/0005/000361 data/0005/000362 data/0005/000363 data/0005/000364 data/0005/000365 data/0005/000366 data/0005/000367 data/0005/000368 data/0005/000369 data/0005/000370 data/0005/000371 data/0005/000372 data/0005/000373 data/0005/000374 data/0005/000375 data/0005/000376 data/0005/000377 data/0005/000378 data/0005/000379 data/0005/000380 data/0005/000381 data/0005/000382 data/0005/000383 data/0005/000384 data/0005/000385 data/0005/000386 data/0005/000387 data/0005/000388 data/0005/000389 data/0005/000390 data/0005/000391 data/0005/000392 data/0005/000393 data/0005/000394 data/0005/000395 data/0005/000396 data/0005/000397 data/0005/000398 data/0005/000399 data/0005/000400 data/0005/000401 data/0005/000402 data/0005/000403 data/0005/000404 data/0005/000405 data/0005/000406 data/0005/000407 data/0005/000408 data/0005/000409 data/0005/000410 data/0005/000411 data/0005/000412 data/0005/000413 data/0005/000414 data/0005/000415 data/0005/000416 data/0005/000417 data/0005/000418 data/0005/000419 data/0005/000420 data/0005/000421 data/0005/000422 data/0005/000423 data/0005/000424 data/0005/000425 data/0005/000426 data/0005/000427 data/0005/000428 data/0005/000429 data/0005/000430 data/0005/000431 data/0005/000432 data/0005/000433 data/0005/000434 data/0005/000435 data/0005/000436 data/0005/000437 data/0005/000438 data/0005/000439 data/0005/000440 data/0005/000441 data/0005/000442 data/0005/000443 data/0005/000444 data/0005/000445 data/0005/000446 data/0005/000447 data/0005/000448 data/0005/000449 data/0005/000450 data/0005/000451 data/0005/000452 data/0005/000453 data/0005/000454 data/0005/000455 data/0005/000456 data/0005/000457 data/0005/000458 data/0005/000459 data/0005/000460 data/0005/000461 data/0005/000462 data/0005/000463 data/0005/000464 data/0005/000465 data/0005/000466 data/0005/000467 data/0005/000468 data/0005/000469 data/0005/000470 data/0005/000471 data/0005/000472 data/0005/000473 data/0005/000474 data/0005/000475 data/0005/000476 data/0005/000477 data/0005/000478 data/0005/000479 data/0005/000480 data/0005/000481 data/0005/000482 data/0005/000483 data/0005/000484 data/0005/000485 data/0005/000486 data/0005/000487 data/0005/000488 data/0005/000489 data/0005/000490 data/0005/000491 data/0005/000492 data/0005/000493 data/0005/000494 data/0005/000495 data/0005/000496 data/0005/000497 data/0005/000498 data/0005/000499 data/0005/000500 data/0005/000501 data/0005/000502 data/0005/000503 data/0005/000504 data/0005/000505 data/0005/000506 data/0005/000507 data/0005/000508 data/0005/000509 data/0005/000510 data/0005/000511 data/0005/000512 data/0005/000513 data/0005/000514 data/0005/000515 data/0005/000516 data/0005/000517 data/0005/000518 data/0005/000519 data/0005/000520 data/0005/000521 data/0005/000522 data/0005/000523 data/0005/000524 data/0005/000525 data/0005/000526 data/0005/000527 data/0005/000528 data/0005/000529 data/0005/000530 data/0005/000531 data/0005/000532 data/0005/000533 data/0005/000534 data/0005/000535 data/0005/000536 data/0005/000537 data/0005/000538 data/0005/000539 data/0005/000540 data/0005/000541 data/0005/000542 data/0005/000543 data/0005/000544 data/0005/000545 data/0005/000546 data/0005/000547 data/0005/000548 data/0005/000549 data/0005/000550 data/0005/000551 data/0005/000552 data/0005/000553 data/0005/000554 data/0005/000555 data/0005/000556 data/0005/000557 data/0005/000558 data/0005/000559 data/0005/000560 data/0005/000561 data/0005/000562 data/0005/000563 data/0005/000564 data/0005/000565 data/0005/000566 data/0005/000567 data/0005/000568 data/0005/000569 data/0005/000570 data/0005/000571 data/0005/000572 data/0005/000573 data/0005/000574 data/0005/000575 data/0005/000576 data/0005/000577 data/0005/000578 data/0005/000579 data/0005/000580 data/0005/000581 data/0005/000582 data/0005/000583 data/0005/000584 data/0005/000585 data/0005/000586 data/0005/000587 data/0005/000588 data/0005/000589 data/0005/000590 data/0005/000591 data/0005/000592 data/0005/000593 data/0005/000594 data/0005/000595 data/0005/000596 data/0005/000597 data/0005/000598 data/0005/000599 data/0005/000600 data/0005/000601 data/0005/000602 data/0005/000603 data/0005/000604 data/0005/000605 data/0005/000606 data/0005/000607 data/0005/000608 data/0005/000609 data/0005/000610 data/0005/000611 data/0005/000612 data/0005/000613 data/0005/000614 data/0005/000615 data/0005/000616 data/0005/000617 data/0005/000618 data/0005/000619 data/0005/000620 data/0005/000621 data/0005/000622 data/0005/000623 data/0005/000624 data/0005/000625 data/0005/000626 data/0005/000627 data/0005/000628 data/0005/000629 data/0005/000630 data/0005/000631 data/0005/000632 data/0005/000633 data/0005/000634 data/0005/000635 data/0005/000636 data/0005/000637 data/0005/000638 data/0005/000639 data/0005/000640 data/0005/000641 data/0005/000642 data/0005/000643 data/0005/000644 data/0005/000645 data/0005/000646 data/0005/000647 data/0005/000648 data/0005/000649 data/0005/000650 data/0005/000651 data/0005/000652 data/0005/000653 data/0005/000654 data/0005/000655 data/0005/000656 data/0005/000657 data/0005/000658 data/0005/000659 data/0005/000660 data/0005/000661 data/0005/000662 data/0005/000663 data/0005/000664 data/0005/000665 data/0005/000666 data/0005/000667 data/0005/000668 data/0005/000669 data/0005/000670 data/0005/000671 data/0005/000672 data/0005/000673 data/0005/000674 data/0005/000675 data/0005/000676 data/0005/000677 data/0005/000678 data/0005/000679 data/0005/000680 data/0005/000681 data/0005/000682 data/0005/000683 data/0005/000684 data/0005/000685 data/0005/000686 data/0005/000687 data/0005/000688 data/0005/000689 data/0005/000690 data/0005/000691 data/0005/000692 data/0005/000693 data/0005/000694 data/0005/000695 data/0005/000696 data/0005/000697 data/0005/000698 data/0005/000699 data/0005/000700 data/0005/000701 data/0005/000702 data/0005/000703 data/0005/000704 data/0005/000705 data/0005/000706 data/0005/000707 data/0005/000708 data/0005/000709 data/0005/000710 data/0005/000711 data/0005/000712 data/0005/000713 data/0005/000714 data/0005/000715 data/0005/000716 data/0005/000717 data/0005/000718 data/0005/000719 data/0005/000720 data/0005/000721 data/0005/000722 data/0005/000723 data/0005/000724 data/0005/000725 data/0005/000726 data/0005/000727 data/0005/000728 data/0005/000729 data/0005/000730 data/0005/000731 data/0005/000732 data/0005/000733 data/0005/000734 data/0005/000735 data/0005/000736 data/0005/000737 data/0005/000738 data/0005/000739 data/0005/000740 data/0005/000741 data/0005/000742 data/0005/000743 data/0005/000744 data/0005/000745 data/0005/000746 data/0005/000747 data/0005/000748 data/0005/000749 data/0005/000750 data/0005/000751 data/0005/000752 data/0005/000753 data/0005/000754 data/0005/000755 data/0005/000756 data/0005/000757 data/0005/000758 data/0005/000759 data/0005/000760 data/0005/000761 data/0005/000762 data/0005/000763 data/0005/000764 data/0005/000765 data/0005/000766 data/0005/000767 data/0005/000768 data/0005/000769 data/0005/000770 data/0005/000771 data/0005/000772 data/0005/000773 data/0005/000774 data/0005/000775 data/0005/000776 data/0005/000777 data/0005/000778 data/0005/000779 data/0005/000780 data/0005/000781 data/0005/000782 data/0005/000783 data/0005/000784 data/0005/000785 data/0005/000786 data/0005/000787 data/0005/000788 data/0005/000789 data/0005/000790 data/0005/000791 data/0005/000792 data/0005/000793 data/0005/000794 data/0005/000795 data/0005/000796 data/0005/000797 data/0005/000798 data/0005/000799 data/0005/000800 data/0005/000801 data/0005/000802 data/0005/000803 data/0005/000804 data/0005/000805 data/0005/000806 data/0005/000807 data/0005/000808 data/0005/000809 data/0005/000810 data/0005/000811 data/0005/000812 data/0005/000813 data/0005/000814 data/0005/000815 data/0005/000816 data/0005/000817 data/0005/000818 data/0005/000819 data/0005/000820 data/0005/000821 data/0005/000822 data/0005/000823 data/0005/000824 data/0005/000825 data/0005/000826 data/0005/000827 data/0005/000828 data/0006/000001 data/0006/000002 data/0006/000003 data/0006/000004 data/0006/000005 data/0006/000006 data/0006/000007 data/0006/000008 data/0006/000009 data/0006/000010 data/0006/000011 data/0006/000012 data/0006/000013 data/0006/000014 data/0006/000015 data/0006/000016 data/0006/000017 data/0006/000018 data/0006/000019 data/0006/000020 data/0006/000021 data/0006/000022 data/0006/000023 data/0006/000024 data/0006/000025 data/0006/000026 data/0006/000027 data/0006/000028 data/0006/000029 data/0006/000030 data/0006/000031 data/0006/000032 data/0006/000033 data/0006/000034 data/0006/000035 data/0006/000036 data/0006/000037 data/0006/000038 data/0006/000039 data/0006/000040 data/0006/000041 data/0006/000042 data/0006/000043 data/0006/000044 data/0006/000045 data/0006/000046 data/0006/000047 data/0006/000048 data/0006/000049 data/0006/000050 data/0006/000051 data/0006/000052 data/0006/000053 data/0006/000054 data/0006/000055 data/0006/000056 data/0006/000057 data/0006/000058 data/0006/000059 data/0006/000060 data/0006/000061 data/0006/000062 data/0006/000063 data/0006/000064 data/0006/000065 data/0006/000066 data/0006/000067 data/0006/000068 data/0006/000069 data/0006/000070 data/0006/000071 data/0006/000072 data/0006/000073 data/0006/000074 data/0006/000075 data/0006/000076 data/0006/000077 data/0006/000078 data/0006/000079 data/0006/000080 data/0006/000081 data/0006/000082 data/0006/000083 data/0006/000084 data/0006/000085 data/0006/000086 data/0006/000087 data/0006/000088 data/0006/000089 data/0006/000090 data/0006/000091 data/0006/000092 data/0006/000093 data/0006/000094 data/0006/000095 data/0006/000096 data/0006/000097 data/0006/000098 data/0006/000099 data/0006/000100 data/0006/000101 data/0006/000102 data/0006/000103 data/0006/000104 data/0006/000105 data/0006/000106 data/0006/000107 data/0006/000108 data/0006/000109 data/0006/000110 data/0006/000111 data/0006/000112 data/0006/000113 data/0006/000114 data/0006/000115 data/0006/000116 data/0006/000117 data/0006/000118 data/0006/000119 data/0006/000120 data/0006/000121 data/0006/000122 data/0006/000123 data/0006/000124 data/0006/000125 data/0006/000126 data/0006/000127 data/0006/000128 data/0006/000129 data/0006/000130 data/0006/000131 data/0006/000132 data/0006/000133 data/0006/000134 data/0006/000135 data/0006/000136 data/0006/000137 data/0006/000138 data/0006/000139 data/0006/000140 data/0006/000141 data/0006/000142 data/0006/000143 data/0006/000144 data/0006/000145 data/0006/000146 data/0006/000147 data/0006/000148 data/0006/000149 data/0006/000150 data/0006/000151 data/0006/000152 data/0006/000153 data/0006/000154 data/0006/000155 data/0006/000156 data/0006/000157 data/0006/000158 data/0006/000159 data/0006/000160 data/0006/000161 data/0006/000162 data/0006/000163 data/0006/000164 data/0006/000165 data/0006/000166 data/0006/000167 data/0006/000168 data/0006/000169 data/0006/000170 data/0006/000171 data/0006/000172 data/0006/000173 data/0006/000174 data/0006/000175 data/0006/000176 data/0006/000177 data/0006/000178 data/0006/000179 data/0006/000180 data/0006/000181 data/0006/000182 data/0006/000183 data/0006/000184 data/0006/000185 data/0006/000186 data/0006/000187 data/0006/000188 data/0006/000189 data/0006/000190 data/0006/000191 data/0006/000192 data/0006/000193 data/0006/000194 data/0006/000195 data/0006/000196 data/0006/000197 data/0006/000198 data/0006/000199 data/0006/000200 data/0006/000201 data/0006/000202 data/0006/000203 data/0006/000204 data/0006/000205 data/0006/000206 data/0006/000207 data/0006/000208 data/0006/000209 data/0006/000210 data/0006/000211 data/0006/000212 data/0006/000213 data/0006/000214 data/0006/000215 data/0006/000216 data/0006/000217 data/0006/000218 data/0006/000219 data/0006/000220 data/0006/000221 data/0006/000222 data/0006/000223 data/0006/000224 data/0006/000225 data/0006/000226 data/0006/000227 data/0006/000228 data/0006/000229 data/0006/000230 data/0006/000231 data/0006/000232 data/0006/000233 data/0006/000234 data/0006/000235 data/0006/000236 data/0006/000237 data/0006/000238 data/0006/000239 data/0006/000240 data/0006/000241 data/0006/000242 data/0006/000243 data/0006/000244 data/0006/000245 data/0006/000246 data/0006/000247 data/0006/000248 data/0006/000249 data/0006/000250 data/0006/000251 data/0006/000252 data/0006/000253 data/0006/000254 data/0006/000255 data/0006/000256 data/0006/000257 data/0006/000258 data/0006/000259 data/0006/000260 data/0006/000261 data/0006/000262 data/0006/000263 data/0006/000264 data/0006/000265 data/0006/000266 data/0006/000267 data/0006/000268 data/0006/000269 data/0006/000270 data/0006/000271 data/0006/000272 data/0006/000273 data/0006/000274 data/0006/000275 data/0006/000276 data/0006/000277 data/0006/000278 data/0006/000279 data/0006/000280 data/0006/000281 data/0006/000282 data/0006/000283 data/0006/000284 data/0006/000285 data/0006/000286 data/0006/000287 data/0006/000288 data/0006/000289 data/0006/000290 data/0006/000291 data/0006/000292 data/0006/000293 data/0006/000294 data/0006/000295 data/0006/000296 data/0006/000297 data/0006/000298 data/0006/000299 data/0006/000300 data/0006/000301 data/0006/000302 data/0006/000303 data/0006/000304 data/0006/000305 data/0006/000306 data/0006/000307 data/0006/000308 data/0006/000309 data/0006/000310 data/0006/000311 data/0006/000312 data/0006/000313 data/0006/000314 data/0006/000315 data/0006/000316 data/0006/000317 data/0006/000318 data/0006/000319 data/0006/000320 data/0006/000321 data/0006/000322 data/0006/000323 data/0006/000324 data/0006/000325 data/0006/000326 data/0006/000327 data/0006/000328 data/0006/000329 data/0006/000330 data/0006/000331 data/0006/000332 data/0006/000333 data/0006/000334 data/0006/000335 data/0006/000336 data/0006/000337 data/0006/000338 data/0006/000339 data/0006/000340 data/0006/000341 data/0006/000342 data/0006/000343 data/0006/000344 data/0006/000345 data/0006/000346 data/0006/000347 data/0006/000348 data/0006/000349 data/0006/000350 data/0006/000351 data/0006/000352 data/0006/000353 data/0006/000354 data/0006/000355 data/0006/000356 data/0006/000357 data/0006/000358 data/0006/000359 data/0006/000360 data/0006/000361 data/0006/000362 data/0006/000363 data/0006/000364 data/0006/000365 data/0006/000366 data/0006/000367 data/0006/000368 data/0006/000369 data/0006/000370 data/0006/000371 data/0006/000372 data/0006/000373 data/0006/000374 data/0006/000375 data/0006/000376 data/0006/000377 data/0006/000378 data/0006/000379 data/0006/000380 data/0006/000381 data/0006/000382 data/0006/000383 data/0006/000384 data/0006/000385 data/0006/000386 data/0006/000387 data/0006/000388 data/0006/000389 data/0006/000390 data/0006/000391 data/0006/000392 data/0006/000393 data/0006/000394 data/0006/000395 data/0006/000396 data/0006/000397 data/0006/000398 data/0006/000399 data/0006/000400 data/0006/000401 data/0006/000402 data/0006/000403 data/0006/000404 data/0006/000405 data/0006/000406 data/0006/000407 data/0006/000408 data/0006/000409 data/0006/000410 data/0006/000411 data/0006/000412 data/0006/000413 data/0006/000414 data/0006/000415 data/0006/000416 data/0006/000417 data/0006/000418 data/0006/000419 data/0006/000420 data/0006/000421 data/0006/000422 data/0006/000423 data/0006/000424 data/0006/000425 data/0006/000426 data/0006/000427 data/0006/000428 data/0006/000429 data/0006/000430 data/0006/000431 data/0006/000432 data/0006/000433 data/0006/000434 data/0006/000435 data/0006/000436 data/0006/000437 data/0006/000438 data/0006/000439 data/0006/000440 data/0006/000441 data/0006/000442 data/0006/000443 data/0006/000444 data/0006/000445 data/0006/000446 data/0006/000447 data/0006/000448 data/0006/000449 data/0006/000450 data/0006/000451 data/0006/000452 data/0006/000453 data/0006/000454 data/0006/000455 data/0006/000456 data/0006/000457 data/0006/000458 data/0006/000459 data/0006/000460 data/0006/000461 data/0006/000462 data/0006/000463 data/0006/000464 data/0006/000465 data/0006/000466 data/0006/000467 data/0006/000468 data/0006/000469 data/0006/000470 data/0006/000471 data/0006/000472 data/0006/000473 data/0006/000474 data/0006/000475 data/0006/000476 data/0006/000477 data/0006/000478 data/0006/000479 data/0006/000480 data/0006/000481 data/0006/000482 data/0006/000483 data/0006/000484 data/0006/000485 data/0006/000486 data/0006/000487 data/0006/000488 data/0006/000489 data/0006/000490 data/0006/000491 data/0006/000492 data/0006/000493 data/0006/000494 data/0006/000495 data/0006/000496 data/0006/000497 data/0006/000498 data/0006/000499 data/0006/000500 data/0006/000501 data/0006/000502 data/0006/000503 data/0006/000504 data/0006/000505 data/0006/000506 data/0006/000507 data/0006/000508 data/0006/000509 data/0006/000510 data/0006/000511 data/0006/000512 data/0006/000513 data/0006/000514 data/0006/000515 data/0006/000516 data/0006/000517 data/0006/000518 data/0006/000519 data/0006/000520 data/0006/000521 data/0006/000522 data/0006/000523 data/0006/000524 data/0006/000525 data/0006/000526 data/0006/000527 data/0006/000528 data/0006/000529 data/0006/000530 data/0006/000531 data/0006/000532 data/0006/000533 data/0006/000534 data/0006/000535 data/0006/000536 data/0006/000537 data/0006/000538 data/0006/000539 data/0006/000540 data/0006/000541 data/0006/000542 data/0006/000543 data/0006/000544 data/0006/000545 data/0006/000546 data/0006/000547 data/0006/000548 data/0006/000549 data/0006/000550 data/0006/000551 data/0006/000552 data/0006/000553 data/0006/000554 data/0006/000555 data/0006/000556 data/0006/000557 data/0006/000558 data/0006/000559 data/0006/000560 data/0006/000561 data/0006/000562 data/0006/000563 data/0006/000564 data/0006/000565 data/0006/000566 data/0006/000567 data/0006/000568 data/0006/000569 data/0006/000570 data/0006/000571 data/0006/000572 data/0006/000573 data/0006/000574 data/0006/000575 data/0006/000576 data/0006/000577 data/0006/000578 data/0006/000579 data/0006/000580 data/0006/000581 data/0006/000582 data/0006/000583 data/0006/000584 data/0006/000585 data/0006/000586 data/0006/000587 data/0006/000588 data/0006/000589 data/0006/000590 data/0006/000591 data/0006/000592 data/0006/000593 data/0006/000594 data/0006/000595 data/0006/000596 data/0006/000597 data/0006/000598 data/0006/000599 data/0006/000600 data/0006/000601 data/0006/000602 data/0006/000603 data/0006/000604 data/0006/000605 data/0006/000606 data/0006/000607 data/0006/000608 data/0006/000609 data/0006/000610 data/0006/000611 data/0006/000612 data/0006/000613 data/0006/000614 data/0006/000615 data/0006/000616 data/0006/000617 data/0006/000618 data/0006/000619 data/0006/000620 data/0006/000621 data/0006/000622 data/0006/000623 data/0006/000624 data/0006/000625 data/0006/000626 data/0006/000627 data/0006/000628 data/0006/000629 data/0006/000630 data/0006/000631 data/0006/000632 data/0006/000633 data/0006/000634 data/0006/000635 data/0006/000636 data/0006/000637 data/0006/000638 data/0006/000639 data/0006/000640 data/0006/000641 data/0006/000642 data/0006/000643 data/0006/000644 data/0006/000645 data/0006/000646 data/0006/000647 data/0006/000648 data/0006/000649 data/0006/000650 data/0006/000651 data/0006/000652 data/0006/000653 data/0006/000654 data/0006/000655 data/0006/000656 data/0006/000657 data/0006/000658 data/0006/000659 data/0006/000660 data/0006/000661 data/0006/000662 data/0006/000663 data/0006/000664 data/0006/000665 data/0006/000666 data/0006/000667 data/0006/000668 data/0006/000669 data/0006/000670 data/0006/000671 data/0006/000672 data/0006/000673 data/0006/000674 data/0006/000675 data/0006/000676 data/0006/000677 data/0006/000678 data/0006/000679 data/0006/000680 data/0006/000681 data/0006/000682 data/0006/000683 data/0006/000684 data/0006/000685 data/0006/000686 data/0006/000687 data/0006/000688 data/0006/000689 data/0006/000690 data/0006/000691 data/0006/000692 data/0006/000693 data/0006/000694 data/0006/000695 data/0006/000696 data/0006/000697 data/0006/000698 data/0006/000699 data/0006/000700 data/0006/000701 data/0006/000702 data/0006/000703 data/0006/000704 data/0006/000705 data/0006/000706 data/0006/000707 data/0006/000708 data/0006/000709 data/0006/000710 data/0006/000711 data/0006/000712 data/0006/000713 data/0006/000714 data/0006/000715 data/0006/000716 data/0006/000717 data/0006/000718 data/0006/000719 data/0006/000720 data/0006/000721 data/0006/000722 data/0006/000723 data/0006/000724 data/0006/000725 data/0006/000726 data/0006/000727 data/0006/000728 data/0006/000729 data/0006/000730 data/0006/000731 data/0006/000732 data/0006/000733 data/0006/000734 data/0006/000735 data/0006/000736 data/0006/000737 data/0006/000738 data/0006/000739 data/0006/000740 data/0006/000741 data/0006/000742 data/0006/000743 data/0006/000744 data/0006/000745 data/0006/000746 data/0006/000747 data/0006/000748 data/0006/000749 data/0006/000750 data/0006/000751 data/0006/000752 data/0006/000753 data/0006/000754 data/0006/000755 data/0006/000756 data/0006/000757 data/0006/000758 data/0006/000759 data/0006/000760 data/0006/000761 data/0006/000762 data/0006/000763 data/0006/000764 data/0006/000765 data/0006/000766 data/0006/000767 data/0006/000768 data/0006/000769 data/0006/000770 data/0006/000771 data/0006/000772 data/0006/000773 data/0006/000774 data/0006/000775 data/0006/000776 data/0006/000777 data/0006/000778 data/0006/000779 data/0006/000780 data/0006/000781 data/0006/000782 data/0006/000783 data/0006/000784 data/0006/000785 data/0006/000786 data/0006/000787 data/0006/000788 data/0006/000789 data/0006/000790 data/0006/000791 data/0006/000792 data/0006/000793 data/0006/000794 data/0006/000795 data/0006/000796 data/0006/000797 data/0006/000798 data/0006/000799 data/0006/000800 data/0006/000801 data/0006/000802 data/0006/000803 data/0006/000804 data/0006/000805 data/0006/000806 data/0006/000807 data/0006/000808 data/0006/000809 data/0006/000810 data/0006/000811 data/0006/000812 data/0006/000813 data/0006/000814 data/0006/000815 data/0006/000816 data/0006/000817 data/0006/000818 data/0006/000819 data/0006/000820 data/0006/000821 data/0006/000822 data/0006/000823 data/0007/000001 data/0007/000002 data/0007/000003 data/0007/000004 data/0007/000005 data/0007/000006 data/0007/000007 data/0007/000008 data/0007/000009 data/0007/000010 data/0007/000011 data/0007/000012 data/0007/000013 data/0007/000014 data/0007/000015 data/0007/000016 data/0007/000017 data/0007/000018 data/0007/000019 data/0007/000020 data/0007/000021 data/0007/000022 data/0007/000023 data/0007/000024 data/0007/000025 data/0007/000026 data/0007/000027 data/0007/000028 data/0007/000029 data/0007/000030 data/0007/000031 data/0007/000032 data/0007/000033 data/0007/000034 data/0007/000035 data/0007/000036 data/0007/000037 data/0007/000038 data/0007/000039 data/0007/000040 data/0007/000041 data/0007/000042 data/0007/000043 data/0007/000044 data/0007/000045 data/0007/000046 data/0007/000047 data/0007/000048 data/0007/000049 data/0007/000050 data/0007/000051 data/0007/000052 data/0007/000053 data/0007/000054 data/0007/000055 data/0007/000056 data/0007/000057 data/0007/000058 data/0007/000059 data/0007/000060 data/0007/000061 data/0007/000062 data/0007/000063 data/0007/000064 data/0007/000065 data/0007/000066 data/0007/000067 data/0007/000068 data/0007/000069 data/0007/000070 data/0007/000071 data/0007/000072 data/0007/000073 data/0007/000074 data/0007/000075 data/0007/000076 data/0007/000077 data/0007/000078 data/0007/000079 data/0007/000080 data/0007/000081 data/0007/000082 data/0007/000083 data/0007/000084 data/0007/000085 data/0007/000086 data/0007/000087 data/0007/000088 data/0007/000089 data/0007/000090 data/0007/000091 data/0007/000092 data/0007/000093 data/0007/000094 data/0007/000095 data/0007/000096 data/0007/000097 data/0007/000098 data/0007/000099 data/0007/000100 data/0007/000101 data/0007/000102 data/0007/000103 data/0007/000104 data/0007/000105 data/0007/000106 data/0007/000107 data/0007/000108 data/0007/000109 data/0007/000110 data/0007/000111 data/0007/000112 data/0007/000113 data/0007/000114 data/0007/000115 data/0007/000116 data/0007/000117 data/0007/000118 data/0007/000119 data/0007/000120 data/0007/000121 data/0007/000122 data/0007/000123 data/0007/000124 data/0007/000125 data/0007/000126 data/0007/000127 data/0007/000128 data/0007/000129 data/0007/000130 data/0007/000131 data/0007/000132 data/0007/000133 data/0007/000134 data/0007/000135 data/0007/000136 data/0007/000137 data/0007/000138 data/0007/000139 data/0007/000140 data/0007/000141 data/0007/000142 data/0007/000143 data/0007/000144 data/0007/000145 data/0007/000146 data/0007/000147 data/0007/000148 data/0007/000149 data/0007/000150 data/0007/000151 data/0007/000152 data/0007/000153 data/0007/000154 data/0007/000155 data/0007/000156 data/0007/000157 data/0007/000158 data/0007/000159 data/0007/000160 data/0007/000161 data/0007/000162 data/0007/000163 data/0007/000164 data/0007/000165 data/0007/000166 data/0007/000167 data/0007/000168 data/0007/000169 data/0007/000170 data/0007/000171 data/0007/000172 data/0007/000173 data/0007/000174 data/0007/000175 data/0007/000176 data/0007/000177 data/0007/000178 data/0007/000179 data/0007/000180 data/0007/000181 data/0007/000182 data/0007/000183 data/0007/000184 data/0007/000185 data/0007/000186 data/0007/000187 data/0007/000188 data/0007/000189 data/0007/000190 data/0007/000191 data/0007/000192 data/0007/000193 data/0007/000194 data/0007/000195 data/0007/000196 data/0007/000197 data/0007/000198 data/0007/000199 data/0007/000200 data/0007/000201 data/0007/000202 data/0007/000203 data/0007/000204 data/0007/000205 data/0007/000206 data/0007/000207 data/0007/000208 data/0007/000209 data/0007/000210 data/0007/000211 data/0007/000212 data/0007/000213 data/0007/000214 data/0007/000215 data/0007/000216 data/0007/000217 data/0007/000218 data/0007/000219 data/0007/000220 data/0007/000221 data/0007/000222 data/0007/000223 data/0007/000224 data/0007/000225 data/0007/000226 data/0007/000227 data/0007/000228 data/0007/000229 data/0007/000230 data/0007/000231 data/0007/000232 data/0007/000233 data/0007/000234 data/0007/000235 data/0007/000236 data/0007/000237 data/0007/000238 data/0007/000239 data/0007/000240 data/0007/000241 data/0007/000242 data/0007/000243 data/0007/000244 data/0007/000245 data/0007/000246 data/0007/000247 data/0007/000248 data/0007/000249 data/0007/000250 data/0007/000251 data/0007/000252 data/0007/000253 data/0007/000254 data/0007/000255 data/0007/000256 data/0007/000257 data/0007/000258 data/0007/000259 data/0007/000260 data/0007/000261 data/0007/000262 data/0007/000263 data/0007/000264 data/0007/000265 data/0007/000266 data/0007/000267 data/0007/000268 data/0007/000269 data/0007/000270 data/0007/000271 data/0007/000272 data/0007/000273 data/0007/000274 data/0007/000275 data/0007/000276 data/0007/000277 data/0007/000278 data/0007/000279 data/0007/000280 data/0007/000281 data/0007/000282 data/0007/000283 data/0007/000284 data/0007/000285 data/0007/000286 data/0007/000287 data/0007/000288 data/0007/000289 data/0007/000290 data/0007/000291 data/0007/000292 data/0007/000293 data/0007/000294 data/0007/000295 data/0007/000296 data/0007/000297 data/0007/000298 data/0007/000299 data/0007/000300 data/0007/000301 data/0007/000302 data/0007/000303 data/0007/000304 data/0007/000305 data/0007/000306 data/0007/000307 data/0007/000308 data/0007/000309 data/0007/000310 data/0007/000311 data/0007/000312 data/0007/000313 data/0007/000314 data/0007/000315 data/0007/000316 data/0007/000317 data/0007/000318 data/0007/000319 data/0007/000320 data/0007/000321 data/0007/000322 data/0007/000323 data/0007/000324 data/0007/000325 data/0007/000326 data/0007/000327 data/0007/000328 data/0007/000329 data/0007/000330 data/0007/000331 data/0007/000332 data/0007/000333 data/0007/000334 data/0007/000335 data/0007/000336 data/0007/000337 data/0007/000338 data/0007/000339 data/0007/000340 data/0007/000341 data/0007/000342 data/0007/000343 data/0007/000344 data/0007/000345 data/0007/000346 data/0007/000347 data/0007/000348 data/0007/000349 data/0007/000350 data/0007/000351 data/0007/000352 data/0007/000353 data/0007/000354 data/0007/000355 data/0007/000356 data/0007/000357 data/0007/000358 data/0007/000359 data/0007/000360 data/0007/000361 data/0007/000362 data/0007/000363 data/0007/000364 data/0007/000365 data/0007/000366 data/0007/000367 data/0007/000368 data/0007/000369 data/0007/000370 data/0007/000371 data/0007/000372 data/0007/000373 data/0007/000374 data/0007/000375 data/0007/000376 data/0007/000377 data/0007/000378 data/0007/000379 data/0007/000380 data/0007/000381 data/0007/000382 data/0007/000383 data/0007/000384 data/0007/000385 data/0007/000386 data/0007/000387 data/0007/000388 data/0007/000389 data/0007/000390 data/0007/000391 data/0007/000392 data/0007/000393 data/0007/000394 data/0007/000395 data/0007/000396 data/0007/000397 data/0007/000398 data/0007/000399 data/0007/000400 data/0007/000401 data/0007/000402 data/0007/000403 data/0007/000404 data/0007/000405 data/0007/000406 data/0007/000407 data/0007/000408 data/0007/000409 data/0007/000410 data/0007/000411 data/0007/000412 data/0007/000413 data/0007/000414 data/0007/000415 data/0007/000416 data/0007/000417 data/0007/000418 data/0007/000419 data/0007/000420 data/0007/000421 data/0007/000422 data/0007/000423 data/0007/000424 data/0007/000425 data/0007/000426 data/0007/000427 data/0007/000428 data/0007/000429 data/0007/000430 data/0007/000431 data/0007/000432 data/0007/000433 data/0007/000434 data/0007/000435 data/0007/000436 data/0007/000437 data/0007/000438 data/0007/000439 data/0007/000440 data/0007/000441 data/0007/000442 data/0007/000443 data/0007/000444 data/0007/000445 data/0007/000446 data/0007/000447 data/0007/000448 data/0007/000449 data/0007/000450 data/0007/000451 data/0007/000452 data/0007/000453 data/0007/000454 data/0007/000455 data/0007/000456 data/0007/000457 data/0007/000458 data/0007/000459 data/0007/000460 data/0007/000461 data/0007/000462 data/0007/000463 data/0007/000464 data/0007/000465 data/0007/000466 data/0007/000467 data/0007/000468 data/0007/000469 data/0007/000470 data/0007/000471 data/0007/000472 data/0007/000473 data/0007/000474 data/0007/000475 data/0007/000476 data/0007/000477 data/0007/000478 data/0007/000479 data/0007/000480 data/0007/000481 data/0007/000482 data/0007/000483 data/0007/000484 data/0007/000485 data/0007/000486 data/0007/000487 data/0007/000488 data/0007/000489 data/0007/000490 data/0007/000491 data/0007/000492 data/0007/000493 data/0007/000494 data/0007/000495 data/0007/000496 data/0007/000497 data/0007/000498 data/0007/000499 data/0007/000500 data/0007/000501 data/0007/000502 data/0007/000503 data/0007/000504 data/0007/000505 data/0007/000506 data/0007/000507 data/0007/000508 data/0007/000509 data/0007/000510 data/0007/000511 data/0007/000512 data/0007/000513 data/0007/000514 data/0007/000515 data/0007/000516 data/0007/000517 data/0007/000518 data/0007/000519 data/0007/000520 data/0007/000521 data/0007/000522 data/0007/000523 data/0007/000524 data/0007/000525 data/0007/000526 data/0007/000527 data/0007/000528 data/0007/000529 data/0007/000530 data/0007/000531 data/0007/000532 data/0007/000533 data/0007/000534 data/0007/000535 data/0007/000536 data/0007/000537 data/0007/000538 data/0007/000539 data/0007/000540 data/0007/000541 data/0007/000542 data/0007/000543 data/0007/000544 data/0007/000545 data/0007/000546 data/0007/000547 data/0007/000548 data/0007/000549 data/0007/000550 data/0007/000551 data/0007/000552 data/0007/000553 data/0007/000554 data/0007/000555 data/0007/000556 data/0007/000557 data/0007/000558 data/0007/000559 data/0007/000560 data/0007/000561 data/0007/000562 data/0007/000563 data/0007/000564 data/0007/000565 data/0007/000566 data/0007/000567 data/0007/000568 data/0007/000569 data/0007/000570 data/0007/000571 data/0007/000572 data/0007/000573 data/0007/000574 data/0007/000575 data/0007/000576 data/0007/000577 data/0007/000578 data/0007/000579 data/0007/000580 data/0007/000581 data/0007/000582 data/0007/000583 data/0007/000584 data/0007/000585 data/0007/000586 data/0007/000587 data/0007/000588 data/0007/000589 data/0007/000590 data/0007/000591 data/0007/000592 data/0007/000593 data/0007/000594 data/0007/000595 data/0007/000596 data/0007/000597 data/0007/000598 data/0007/000599 data/0007/000600 data/0007/000601 data/0007/000602 data/0007/000603 data/0007/000604 data/0007/000605 data/0007/000606 data/0007/000607 data/0007/000608 data/0007/000609 data/0007/000610 data/0007/000611 data/0007/000612 data/0007/000613 data/0007/000614 data/0007/000615 data/0007/000616 data/0007/000617 data/0007/000618 data/0007/000619 data/0007/000620 data/0007/000621 data/0007/000622 data/0007/000623 data/0007/000624 data/0007/000625 data/0007/000626 data/0007/000627 data/0007/000628 data/0007/000629 data/0007/000630 data/0007/000631 data/0007/000632 data/0007/000633 data/0007/000634 data/0007/000635 data/0007/000636 data/0007/000637 data/0007/000638 data/0007/000639 data/0007/000640 data/0007/000641 data/0007/000642 data/0007/000643 data/0007/000644 data/0007/000645 data/0007/000646 data/0007/000647 data/0007/000648 data/0007/000649 data/0007/000650 data/0007/000651 data/0007/000652 data/0007/000653 data/0007/000654 data/0007/000655 data/0007/000656 data/0007/000657 data/0007/000658 data/0007/000659 data/0007/000660 data/0007/000661 data/0007/000662 data/0007/000663 data/0007/000664 data/0007/000665 data/0007/000666 data/0007/000667 data/0007/000668 data/0007/000669 data/0007/000670 data/0007/000671 data/0007/000672 data/0007/000673 data/0007/000674 data/0007/000675 data/0007/000676 data/0007/000677 data/0007/000678 data/0007/000679 data/0007/000680 data/0007/000681 data/0007/000682 data/0007/000683 data/0007/000684 data/0007/000685 data/0007/000686 data/0007/000687 data/0007/000688 data/0007/000689 data/0007/000690 data/0007/000691 data/0007/000692 data/0007/000693 data/0007/000694 data/0007/000695 data/0007/000696 data/0007/000697 data/0007/000698 data/0007/000699 data/0007/000700 data/0007/000701 data/0007/000702 data/0007/000703 data/0007/000704 data/0007/000705 data/0007/000706 data/0007/000707 data/0007/000708 data/0007/000709 data/0007/000710 data/0007/000711 data/0007/000712 data/0007/000713 data/0007/000714 data/0007/000715 data/0007/000716 data/0007/000717 data/0007/000718 data/0007/000719 data/0007/000720 data/0007/000721 data/0007/000722 data/0007/000723 data/0007/000724 data/0007/000725 data/0007/000726 data/0007/000727 data/0007/000728 data/0007/000729 data/0007/000730 data/0007/000731 data/0007/000732 data/0007/000733 data/0007/000734 data/0007/000735 data/0007/000736 data/0007/000737 data/0007/000738 data/0007/000739 data/0007/000740 data/0007/000741 data/0007/000742 data/0007/000743 data/0007/000744 data/0007/000745 data/0007/000746 data/0007/000747 data/0007/000748 data/0007/000749 data/0007/000750 data/0007/000751 data/0007/000752 data/0007/000753 data/0007/000754 data/0007/000755 data/0007/000756 data/0007/000757 data/0007/000758 data/0007/000759 data/0007/000760 data/0007/000761 data/0007/000762 data/0007/000763 data/0007/000764 data/0007/000765 data/0007/000766 data/0007/000767 data/0007/000768 data/0007/000769 data/0007/000770 data/0007/000771 data/0007/000772 data/0007/000773 data/0007/000774 data/0007/000775 data/0007/000776 data/0007/000777 data/0007/000778 data/0007/000779 data/0007/000780 data/0007/000781 data/0007/000782 data/0007/000783 data/0007/000784 data/0007/000785 data/0007/000786 data/0007/000787 data/0007/000788 data/0007/000789 data/0007/000790 data/0007/000791 data/0007/000792 data/0007/000793 data/0007/000794 data/0007/000795 data/0007/000796 data/0007/000797 data/0007/000798 data/0007/000799 data/0007/000800 data/0007/000801 data/0007/000802 data/0007/000803 data/0007/000804 data/0007/000805 data/0007/000806 data/0007/000807 data/0007/000808 data/0007/000809 data/0007/000810 data/0007/000811 data/0007/000812 data/0007/000813 data/0007/000814 data/0007/000815 data/0007/000816 data/0007/000817 data/0007/000818 data/0007/000819 data/0007/000820 data/0007/000821 data/0007/000822 data/0007/000823 data/0007/000824 data/0007/000825 data/0007/000826 data/0007/000827 data/0007/000828 data/0007/000829 data/0007/000830 data/0007/000831 data/0007/000832 data/0007/000833 data/0007/000834 data/0007/000835 data/0007/000836 data/0007/000837 data/0007/000838 data/0007/000839 data/0007/000840 data/0007/000841 data/0007/000842 data/0007/000843 data/0007/000844 data/0007/000845 data/0007/000846 data/0007/000847 data/0007/000848 data/0007/000849 data/0007/000850 data/0007/000851 data/0007/000852 data/0007/000853 data/0007/000854 data/0007/000855 data/0007/000856 data/0007/000857 data/0007/000858 data/0007/000859 data/0007/000860 data/0007/000861 data/0007/000862 data/0007/000863 data/0007/000864 data/0007/000865 data/0007/000866 data/0007/000867 data/0007/000868 data/0007/000869 data/0007/000870 data/0007/000871 data/0007/000872 data/0007/000873 data/0007/000874 data/0007/000875 data/0007/000876 data/0007/000877 data/0007/000878 data/0007/000879 data/0007/000880 data/0007/000881 data/0007/000882 data/0007/000883 data/0007/000884 data/0007/000885 data/0007/000886 data/0007/000887 data/0007/000888 data/0007/000889 data/0007/000890 data/0007/000891 data/0007/000892 data/0007/000893 data/0007/000894 data/0007/000895 data/0007/000896 data/0007/000897 data/0007/000898 data/0007/000899 data/0007/000900 data/0007/000901 data/0007/000902 data/0007/000903 data/0007/000904 data/0007/000905 data/0007/000906 data/0007/000907 data/0007/000908 data/0007/000909 data/0007/000910 data/0007/000911 data/0007/000912 data/0007/000913 data/0007/000914 data/0007/000915 data/0007/000916 data/0007/000917 data/0007/000918 data/0007/000919 data/0007/000920 data/0007/000921 data/0007/000922 data/0007/000923 data/0007/000924 data/0007/000925 data/0007/000926 data/0007/000927 data/0007/000928 data/0007/000929 data/0007/000930 data/0007/000931 data/0007/000932 data/0007/000933 data/0007/000934 data/0007/000935 data/0007/000936 data/0007/000937 data/0007/000938 data/0007/000939 data/0007/000940 data/0007/000941 data/0007/000942 data/0007/000943 data/0007/000944 data/0007/000945 data/0007/000946 data/0007/000947 data/0007/000948 data/0007/000949 data/0007/000950 data/0007/000951 data/0007/000952 data/0007/000953 data/0007/000954 data/0007/000955 data/0007/000956 data/0007/000957 data/0007/000958 data/0007/000959 data/0007/000960 data/0007/000961 data/0007/000962 data/0007/000963 data/0007/000964 data/0007/000965 data/0007/000966 data/0007/000967 data/0007/000968 data/0008/000001 data/0008/000002 data/0008/000003 data/0008/000004 data/0008/000005 data/0008/000006 data/0008/000007 data/0008/000008 data/0008/000009 data/0008/000010 data/0008/000011 data/0008/000012 data/0008/000013 data/0008/000014 data/0008/000015 data/0008/000016 data/0008/000017 data/0008/000018 data/0008/000019 data/0008/000020 data/0008/000021 data/0008/000022 data/0008/000023 data/0008/000024 data/0008/000025 data/0008/000026 data/0008/000027 data/0008/000028 data/0008/000029 data/0008/000030 data/0008/000031 data/0008/000032 data/0008/000033 data/0008/000034 data/0008/000035 data/0008/000036 data/0008/000037 data/0008/000038 data/0008/000039 data/0008/000040 data/0008/000041 data/0008/000042 data/0008/000043 data/0008/000044 data/0008/000045 data/0008/000046 data/0008/000047 data/0008/000048 data/0008/000049 data/0008/000050 data/0008/000051 data/0008/000052 data/0008/000053 data/0008/000054 data/0008/000055 data/0008/000056 data/0008/000057 data/0008/000058 data/0008/000059 data/0008/000060 data/0008/000061 data/0008/000062 data/0008/000063 data/0008/000064 data/0008/000065 data/0008/000066 data/0008/000067 data/0008/000068 data/0008/000069 data/0008/000070 data/0008/000071 data/0008/000072 data/0008/000073 data/0008/000074 data/0008/000075 data/0008/000076 data/0008/000077 data/0008/000078 data/0008/000079 data/0008/000080 data/0008/000081 data/0008/000082 data/0008/000083 data/0008/000084 data/0008/000085 data/0008/000086 data/0008/000087 data/0008/000088 data/0008/000089 data/0008/000090 data/0008/000091 data/0008/000092 data/0008/000093 data/0008/000094 data/0008/000095 data/0008/000096 data/0008/000097 data/0008/000098 data/0008/000099 data/0008/000100 data/0008/000101 data/0008/000102 data/0008/000103 data/0008/000104 data/0008/000105 data/0008/000106 data/0008/000107 data/0008/000108 data/0008/000109 data/0008/000110 data/0008/000111 data/0008/000112 data/0008/000113 data/0008/000114 data/0008/000115 data/0008/000116 data/0008/000117 data/0008/000118 data/0008/000119 data/0008/000120 data/0008/000121 data/0008/000122 data/0008/000123 data/0008/000124 data/0008/000125 data/0008/000126 data/0008/000127 data/0008/000128 data/0008/000129 data/0008/000130 data/0008/000131 data/0008/000132 data/0008/000133 data/0008/000134 data/0008/000135 data/0008/000136 data/0008/000137 data/0008/000138 data/0008/000139 data/0008/000140 data/0008/000141 data/0008/000142 data/0008/000143 data/0008/000144 data/0008/000145 data/0008/000146 data/0008/000147 data/0008/000148 data/0008/000149 data/0008/000150 data/0008/000151 data/0008/000152 data/0008/000153 data/0008/000154 data/0008/000155 data/0008/000156 data/0008/000157 data/0008/000158 data/0008/000159 data/0008/000160 data/0008/000161 data/0008/000162 data/0008/000163 data/0008/000164 data/0008/000165 data/0008/000166 data/0008/000167 data/0008/000168 data/0008/000169 data/0008/000170 data/0008/000171 data/0008/000172 data/0008/000173 data/0008/000174 data/0008/000175 data/0008/000176 data/0008/000177 data/0008/000178 data/0008/000179 data/0008/000180 data/0008/000181 data/0008/000182 data/0008/000183 data/0008/000184 data/0008/000185 data/0008/000186 data/0008/000187 data/0008/000188 data/0008/000189 data/0008/000190 data/0008/000191 data/0008/000192 data/0008/000193 data/0008/000194 data/0008/000195 data/0008/000196 data/0008/000197 data/0008/000198 data/0008/000199 data/0008/000200 data/0008/000201 data/0008/000202 data/0008/000203 data/0008/000204 data/0008/000205 data/0008/000206 data/0008/000207 data/0008/000208 data/0008/000209 data/0008/000210 data/0008/000211 data/0008/000212 data/0008/000213 data/0008/000214 data/0008/000215 data/0008/000216 data/0008/000217 data/0008/000218 data/0008/000219 data/0008/000220 data/0008/000221 data/0008/000222 data/0008/000223 data/0008/000224 data/0008/000225 data/0008/000226 data/0008/000227 data/0008/000228 data/0008/000229 data/0008/000230 data/0008/000231 data/0008/000232 data/0008/000233 data/0008/000234 data/0008/000235 data/0008/000236 data/0008/000237 data/0008/000238 data/0008/000239 data/0008/000240 data/0008/000241 data/0008/000242 data/0008/000243 data/0008/000244 data/0008/000245 data/0008/000246 data/0008/000247 data/0008/000248 data/0008/000249 data/0008/000250 data/0008/000251 data/0008/000252 data/0008/000253 data/0008/000254 data/0008/000255 data/0008/000256 data/0008/000257 data/0008/000258 data/0008/000259 data/0008/000260 data/0008/000261 data/0008/000262 data/0008/000263 data/0008/000264 data/0008/000265 data/0008/000266 data/0008/000267 data/0008/000268 data/0008/000269 data/0008/000270 data/0008/000271 data/0008/000272 data/0008/000273 data/0008/000274 data/0008/000275 data/0008/000276 data/0008/000277 data/0008/000278 data/0008/000279 data/0008/000280 data/0008/000281 data/0008/000282 data/0008/000283 data/0008/000284 data/0008/000285 data/0008/000286 data/0008/000287 data/0008/000288 data/0008/000289 data/0008/000290 data/0008/000291 data/0008/000292 data/0008/000293 data/0008/000294 data/0008/000295 data/0008/000296 data/0008/000297 data/0008/000298 data/0008/000299 data/0008/000300 data/0008/000301 data/0008/000302 data/0008/000303 data/0008/000304 data/0008/000305 data/0008/000306 data/0008/000307 data/0008/000308 data/0008/000309 data/0008/000310 data/0008/000311 data/0008/000312 data/0008/000313 data/0008/000314 data/0008/000315 data/0008/000316 data/0008/000317 data/0008/000318 data/0008/000319 data/0008/000320 data/0008/000321 data/0008/000322 data/0008/000323 data/0008/000324 data/0008/000325 data/0008/000326 data/0008/000327 data/0008/000328 data/0008/000329 data/0008/000330 data/0008/000331 data/0008/000332 data/0008/000333 data/0008/000334 data/0008/000335 data/0008/000336 data/0008/000337 data/0008/000338 data/0008/000339 data/0008/000340 data/0008/000341 data/0008/000342 data/0008/000343 data/0008/000344 data/0008/000345 data/0008/000346 data/0008/000347 data/0008/000348 data/0008/000349 data/0008/000350 data/0008/000351 data/0008/000352 data/0008/000353 data/0008/000354 data/0008/000355 data/0008/000356 data/0008/000357 data/0008/000358 data/0008/000359 data/0008/000360 data/0008/000361 data/0008/000362 data/0008/000363 data/0008/000364 data/0008/000365 data/0008/000366 data/0008/000367 data/0008/000368 data/0008/000369 data/0008/000370 data/0008/000371 data/0008/000372 data/0008/000373 data/0008/000374 data/0008/000375 data/0008/000376 data/0008/000377 data/0008/000378 data/0008/000379 data/0008/000380 data/0008/000381 data/0008/000382 data/0008/000383 data/0008/000384 data/0008/000385 data/0008/000386 data/0008/000387 data/0008/000388 data/0008/000389 data/0008/000390 data/0008/000391 data/0008/000392 data/0008/000393 data/0008/000394 data/0008/000395 data/0008/000396 data/0008/000397 data/0008/000398 data/0008/000399 data/0008/000400 data/0008/000401 data/0008/000402 data/0008/000403 data/0008/000404 data/0008/000405 data/0008/000406 data/0008/000407 data/0008/000408 data/0008/000409 data/0008/000410 data/0008/000411 data/0008/000412 data/0008/000413 data/0008/000414 data/0008/000415 data/0008/000416 data/0008/000417 data/0008/000418 data/0008/000419 data/0008/000420 data/0008/000421 data/0008/000422 data/0008/000423 data/0008/000424 data/0008/000425 data/0008/000426 data/0008/000427 data/0008/000428 data/0008/000429 data/0008/000430 data/0008/000431 data/0008/000432 data/0008/000433 data/0008/000434 data/0008/000435 data/0008/000436 data/0008/000437 data/0008/000438 data/0008/000439 data/0008/000440 data/0008/000441 data/0008/000442 data/0008/000443 data/0008/000444 data/0008/000445 data/0008/000446 data/0008/000447 data/0008/000448 data/0008/000449 data/0008/000450 data/0008/000451 data/0008/000452 data/0008/000453 data/0008/000454 data/0008/000455 data/0008/000456 data/0008/000457 data/0008/000458 data/0008/000459 data/0008/000460 data/0008/000461 data/0008/000462 data/0008/000463 data/0008/000464 data/0008/000465 data/0008/000466 data/0008/000467 data/0008/000468 data/0008/000469 data/0008/000470 data/0008/000471 data/0008/000472 data/0008/000473 data/0008/000474 data/0008/000475 data/0008/000476 data/0008/000477 data/0008/000478 data/0008/000479 data/0008/000480 data/0008/000481 data/0008/000482 data/0008/000483 data/0008/000484 data/0008/000485 data/0008/000486 data/0008/000487 data/0008/000488 data/0008/000489 data/0008/000490 data/0008/000491 data/0008/000492 data/0008/000493 data/0008/000494 data/0008/000495 data/0008/000496 data/0008/000497 data/0008/000498 data/0008/000499 data/0008/000500 data/0008/000501 data/0008/000502 data/0008/000503 data/0008/000504 data/0008/000505 data/0008/000506 data/0008/000507 data/0008/000508 data/0008/000509 data/0008/000510 data/0008/000511 data/0008/000512 data/0008/000513 data/0008/000514 data/0008/000515 data/0008/000516 data/0008/000517 data/0008/000518 data/0008/000519 data/0008/000520 data/0008/000521 data/0008/000522 data/0008/000523 data/0008/000524 data/0008/000525 data/0008/000526 data/0008/000527 data/0008/000528 data/0008/000529 data/0008/000530 data/0008/000531 data/0008/000532 data/0008/000533 data/0008/000534 data/0008/000535 data/0008/000536 data/0008/000537 data/0008/000538 data/0008/000539 data/0008/000540 data/0008/000541 data/0008/000542 data/0008/000543 data/0008/000544 data/0008/000545 data/0008/000546 data/0008/000547 data/0008/000548 data/0008/000549 data/0008/000550 data/0008/000551 data/0008/000552 data/0008/000553 data/0008/000554 data/0008/000555 data/0008/000556 data/0008/000557 data/0008/000558 data/0008/000559 data/0008/000560 data/0008/000561 data/0008/000562 data/0008/000563 data/0008/000564 data/0008/000565 data/0008/000566 data/0008/000567 data/0008/000568 data/0008/000569 data/0008/000570 data/0008/000571 data/0008/000572 data/0008/000573 data/0008/000574 data/0008/000575 data/0008/000576 data/0008/000577 data/0008/000578 data/0008/000579 data/0008/000580 data/0008/000581 data/0008/000582 data/0008/000583 data/0008/000584 data/0008/000585 data/0008/000586 data/0008/000587 data/0008/000588 data/0008/000589 data/0008/000590 data/0008/000591 data/0008/000592 data/0008/000593 data/0008/000594 data/0008/000595 data/0008/000596 data/0008/000597 data/0008/000598 data/0008/000599 data/0008/000600 data/0008/000601 data/0008/000602 data/0008/000603 data/0008/000604 data/0008/000605 data/0008/000606 data/0008/000607 data/0008/000608 data/0008/000609 data/0008/000610 data/0008/000611 data/0008/000612 data/0008/000613 data/0008/000614 data/0008/000615 data/0008/000616 data/0008/000617 data/0008/000618 data/0008/000619 data/0008/000620 data/0008/000621 data/0008/000622 data/0008/000623 data/0008/000624 data/0008/000625 data/0008/000626 data/0008/000627 data/0008/000628 data/0008/000629 data/0008/000630 data/0008/000631 data/0008/000632 data/0008/000633 data/0008/000634 data/0008/000635 data/0008/000636 data/0009/000001 data/0009/000002 data/0009/000003 data/0009/000004 data/0009/000005 data/0009/000006 data/0009/000007 data/0009/000008 data/0009/000009 data/0009/000010 data/0009/000011 data/0009/000012 data/0009/000013 data/0009/000014 data/0009/000015 data/0009/000016 data/0009/000017 data/0009/000018 data/0009/000019 data/0009/000020 data/0009/000021 data/0009/000022 data/0009/000023 data/0009/000024 data/0009/000025 data/0009/000026 data/0009/000027 data/0009/000028 data/0009/000029 data/0009/000030 data/0009/000031 data/0009/000032 data/0009/000033 data/0009/000034 data/0009/000035 data/0009/000036 data/0009/000037 data/0009/000038 data/0009/000039 data/0009/000040 data/0009/000041 data/0009/000042 data/0009/000043 data/0009/000044 data/0009/000045 data/0009/000046 data/0009/000047 data/0009/000048 data/0009/000049 data/0009/000050 data/0009/000051 data/0009/000052 data/0009/000053 data/0009/000054 data/0009/000055 data/0009/000056 data/0009/000057 data/0009/000058 data/0009/000059 data/0009/000060 data/0009/000061 data/0009/000062 data/0009/000063 data/0009/000064 data/0009/000065 data/0009/000066 data/0009/000067 data/0009/000068 data/0009/000069 data/0009/000070 data/0009/000071 data/0009/000072 data/0009/000073 data/0009/000074 data/0009/000075 data/0009/000076 data/0009/000077 data/0009/000078 data/0009/000079 data/0009/000080 data/0009/000081 data/0009/000082 data/0009/000083 data/0009/000084 data/0009/000085 data/0009/000086 data/0009/000087 data/0009/000088 data/0009/000089 data/0009/000090 data/0009/000091 data/0009/000092 data/0009/000093 data/0009/000094 data/0009/000095 data/0009/000096 data/0009/000097 data/0009/000098 data/0009/000099 data/0009/000100 data/0009/000101 data/0009/000102 data/0009/000103 data/0009/000104 data/0009/000105 data/0009/000106 data/0009/000107 data/0009/000108 data/0009/000109 data/0009/000110 data/0009/000111 data/0009/000112 data/0009/000113 data/0009/000114 data/0009/000115 data/0009/000116 data/0009/000117 data/0009/000118 data/0009/000119 data/0009/000120 data/0009/000121 data/0009/000122 data/0009/000123 data/0009/000124 data/0009/000125 data/0009/000126 data/0009/000127 data/0009/000128 data/0009/000129 data/0009/000130 data/0009/000131 data/0009/000132 data/0009/000133 data/0009/000134 data/0009/000135 data/0009/000136 data/0009/000137 data/0009/000138 data/0009/000139 data/0009/000140 data/0009/000141 data/0009/000142 data/0009/000143 data/0009/000144 data/0009/000145 data/0009/000146 data/0009/000147 data/0009/000148 data/0009/000149 data/0009/000150 data/0009/000151 data/0009/000152 data/0009/000153 data/0009/000154 data/0009/000155 data/0009/000156 data/0009/000157 data/0009/000158 data/0009/000159 data/0009/000160 data/0009/000161 data/0009/000162 data/0009/000163 data/0009/000164 data/0009/000165 data/0009/000166 data/0009/000167 data/0009/000168 data/0009/000169 data/0009/000170 data/0009/000171 data/0009/000172 data/0009/000173 data/0009/000174 data/0009/000175 data/0009/000176 data/0009/000177 data/0009/000178 data/0009/000179 data/0009/000180 data/0009/000181 data/0009/000182 data/0009/000183 data/0009/000184 data/0009/000185 data/0009/000186 data/0009/000187 data/0009/000188 data/0009/000189 data/0009/000190 data/0009/000191 data/0009/000192 data/0009/000193 data/0009/000194 data/0009/000195 data/0009/000196 data/0009/000197 data/0009/000198 data/0009/000199 data/0009/000200 data/0009/000201 data/0009/000202 data/0009/000203 data/0009/000204 data/0009/000205 data/0009/000206 data/0009/000207 data/0009/000208 data/0009/000209 data/0009/000210 data/0009/000211 data/0009/000212 data/0009/000213 data/0009/000214 data/0009/000215 data/0009/000216 data/0009/000217 data/0009/000218 data/0009/000219 data/0009/000220 data/0009/000221 data/0009/000222 data/0009/000223 data/0009/000224 data/0009/000225 data/0009/000226 data/0009/000227 data/0009/000228 data/0009/000229 data/0009/000230 data/0009/000231 data/0009/000232 data/0009/000233 data/0009/000234 data/0009/000235 data/0009/000236 data/0009/000237 data/0009/000238 data/0009/000239 data/0009/000240 data/0009/000241 data/0009/000242 data/0009/000243 data/0009/000244 data/0009/000245 data/0009/000246 data/0009/000247 data/0009/000248 data/0009/000249 data/0009/000250 data/0009/000251 data/0009/000252 data/0009/000253 data/0009/000254 data/0009/000255 data/0009/000256 data/0009/000257 data/0009/000258 data/0009/000259 data/0009/000260 data/0009/000261 data/0009/000262 data/0009/000263 data/0009/000264 data/0009/000265 data/0009/000266 data/0009/000267 data/0009/000268 data/0009/000269 data/0009/000270 data/0009/000271 data/0009/000272 data/0009/000273 data/0009/000274 data/0009/000275 data/0009/000276 data/0009/000277 data/0009/000278 data/0009/000279 data/0009/000280 data/0009/000281 data/0009/000282 data/0009/000283 data/0009/000284 data/0009/000285 data/0009/000286 data/0009/000287 data/0009/000288 data/0009/000289 data/0009/000290 data/0009/000291 data/0009/000292 data/0009/000293 data/0009/000294 data/0009/000295 data/0009/000296 data/0009/000297 data/0009/000298 data/0009/000299 data/0009/000300 data/0009/000301 data/0009/000302 data/0009/000303 data/0009/000304 data/0009/000305 data/0009/000306 data/0009/000307 data/0009/000308 data/0009/000309 data/0009/000310 data/0009/000311 data/0009/000312 data/0009/000313 data/0009/000314 data/0009/000315 data/0009/000316 data/0009/000317 data/0009/000318 data/0009/000319 data/0009/000320 data/0009/000321 data/0009/000322 data/0009/000323 data/0009/000324 data/0009/000325 data/0009/000326 data/0009/000327 data/0009/000328 data/0009/000329 data/0009/000330 data/0009/000331 data/0009/000332 data/0009/000333 data/0009/000334 data/0009/000335 data/0009/000336 data/0009/000337 data/0009/000338 data/0009/000339 data/0009/000340 data/0009/000341 data/0009/000342 data/0009/000343 data/0009/000344 data/0009/000345 data/0009/000346 data/0009/000347 data/0009/000348 data/0009/000349 data/0009/000350 data/0009/000351 data/0009/000352 data/0009/000353 data/0009/000354 data/0009/000355 data/0009/000356 data/0009/000357 data/0009/000358 data/0009/000359 data/0009/000360 data/0009/000361 data/0009/000362 data/0009/000363 data/0009/000364 data/0009/000365 data/0009/000366 data/0009/000367 data/0009/000368 data/0009/000369 data/0009/000370 data/0009/000371 data/0009/000372 data/0009/000373 data/0009/000374 data/0009/000375 data/0009/000376 data/0009/000377 data/0009/000378 data/0009/000379 data/0009/000380 data/0009/000381 data/0009/000382 data/0009/000383 data/0009/000384 data/0009/000385 data/0009/000386 data/0009/000387 data/0009/000388 data/0009/000389 data/0009/000390 data/0009/000391 data/0009/000392 data/0009/000393 data/0009/000394 data/0009/000395 data/0009/000396 data/0009/000397 data/0009/000398 data/0009/000399 data/0009/000400 data/0009/000401 data/0009/000402 data/0009/000403 data/0009/000404 data/0009/000405 data/0009/000406 data/0009/000407 data/0009/000408 data/0009/000409 data/0009/000410 data/0009/000411 data/0009/000412 data/0009/000413 data/0009/000414 data/0009/000415 data/0009/000416 data/0009/000417 data/0009/000418 data/0009/000419 data/0009/000420 data/0009/000421 data/0009/000422 data/0009/000423 data/0009/000424 data/0009/000425 data/0009/000426 data/0009/000427 data/0009/000428 data/0009/000429 data/0009/000430 data/0009/000431 data/0009/000432 data/0009/000433 data/0009/000434 data/0009/000435 data/0009/000436 data/0009/000437 data/0009/000438 data/0009/000439 data/0009/000440 data/0009/000441 data/0009/000442 data/0009/000443 data/0009/000444 data/0009/000445 data/0009/000446 data/0009/000447 data/0009/000448 data/0009/000449 data/0009/000450 data/0009/000451 data/0009/000452 data/0009/000453 data/0009/000454 data/0009/000455 data/0009/000456 data/0009/000457 data/0009/000458 data/0009/000459 data/0009/000460 data/0009/000461 data/0009/000462 data/0009/000463 data/0009/000464 data/0009/000465 data/0009/000466 data/0009/000467 data/0009/000468 data/0009/000469 data/0009/000470 data/0009/000471 data/0009/000472 data/0009/000473 data/0009/000474 data/0009/000475 data/0009/000476 data/0009/000477 data/0009/000478 data/0009/000479 data/0009/000480 data/0009/000481 data/0009/000482 data/0009/000483 data/0009/000484 data/0009/000485 data/0009/000486 data/0009/000487 data/0009/000488 data/0009/000489 data/0009/000490 data/0009/000491 data/0009/000492 data/0009/000493 data/0009/000494 data/0009/000495 data/0009/000496 data/0009/000497 data/0009/000498 data/0009/000499 data/0009/000500 data/0009/000501 data/0009/000502 data/0009/000503 data/0009/000504 data/0009/000505 data/0009/000506 data/0009/000507 data/0009/000508 data/0009/000509 data/0009/000510 data/0009/000511 data/0009/000512 data/0009/000513 data/0009/000514 data/0009/000515 data/0009/000516 data/0009/000517 data/0009/000518 data/0009/000519 data/0009/000520 data/0009/000521 data/0009/000522 data/0009/000523 data/0009/000524 data/0009/000525 data/0009/000526 data/0009/000527 data/0009/000528 data/0009/000529 data/0009/000530 data/0009/000531 data/0009/000532 data/0009/000533 data/0009/000534 data/0009/000535 data/0009/000536 data/0009/000537 data/0009/000538 data/0009/000539 data/0009/000540 data/0009/000541 data/0009/000542 data/0009/000543 data/0009/000544 data/0009/000545 data/0009/000546 data/0009/000547 data/0009/000548 data/0009/000549 data/0009/000550 data/0009/000551 data/0009/000552 data/0009/000553 data/0009/000554 data/0009/000555 data/0009/000556 data/0009/000557 data/0009/000558 data/0009/000559 data/0009/000560 data/0009/000561 data/0009/000562 data/0009/000563 data/0009/000564 data/0009/000565 data/0009/000566 data/0009/000567 data/0009/000568 data/0009/000569 data/0009/000570 data/0009/000571 data/0009/000572 data/0009/000573 data/0009/000574 data/0009/000575 data/0009/000576 data/0009/000577 data/0009/000578 data/0009/000579 data/0009/000580 data/0009/000581 data/0009/000582 data/0009/000583 data/0009/000584 data/0009/000585 data/0009/000586 data/0009/000587 data/0009/000588 data/0009/000589 data/0009/000590 data/0009/000591 data/0009/000592 data/0009/000593 data/0009/000594 data/0009/000595 data/0009/000596 data/0009/000597 data/0009/000598 data/0009/000599 data/0009/000600 data/0009/000601 data/0009/000602 data/0009/000603 data/0009/000604 data/0009/000605 data/0009/000606 data/0009/000607 data/0009/000608 data/0009/000609 data/0009/000610 data/0009/000611 data/0009/000612 data/0009/000613 data/0009/000614 data/0009/000615 data/0009/000616 data/0009/000617 data/0009/000618 data/0009/000619 data/0009/000620 data/0009/000621 data/0009/000622 data/0009/000623 data/0009/000624 data/0009/000625 data/0009/000626 data/0009/000627 data/0009/000628 data/0009/000629 data/0009/000630 data/0009/000631 data/0009/000632 data/0009/000633 data/0009/000634 data/0009/000635 data/0009/000636 data/0009/000637 data/0009/000638 data/0009/000639 data/0009/000640 data/0009/000641 data/0009/000642 data/0009/000643 data/0009/000644 data/0009/000645 data/0009/000646 data/0009/000647 data/0009/000648 data/0009/000649 data/0009/000650 data/0009/000651 data/0009/000652 data/0009/000653 data/0009/000654 data/0009/000655 data/0009/000656 data/0009/000657 data/0009/000658 data/0009/000659 data/0009/000660 data/0009/000661 data/0009/000662 data/0009/000663 data/0009/000664 data/0009/000665 data/0009/000666 data/0009/000667 data/0009/000668 data/0009/000669 data/0009/000670 data/0009/000671 data/0009/000672 data/0009/000673 data/0009/000674 data/0009/000675 data/0009/000676 data/0009/000677 data/0009/000678 data/0009/000679 data/0009/000680 data/0009/000681 data/0009/000682 data/0009/000683 data/0009/000684 data/0009/000685 data/0009/000686 data/0009/000687 data/0009/000688 data/0009/000689 data/0009/000690 data/0009/000691 data/0009/000692 data/0009/000693 data/0009/000694 data/0009/000695 data/0009/000696 data/0009/000697 data/0009/000698 data/0009/000699 data/0009/000700 data/0009/000701 data/0009/000702 data/0009/000703 data/0009/000704 data/0009/000705 data/0009/000706 data/0009/000707 data/0009/000708 data/0009/000709 data/0009/000710 data/0009/000711 data/0009/000712 data/0009/000713 data/0009/000714 data/0009/000715 data/0009/000716 data/0009/000717 data/0009/000718 data/0009/000719 data/0009/000720 data/0009/000721 data/0009/000722 data/0009/000723 data/0009/000724 data/0009/000725 data/0009/000726 data/0009/000727 data/0009/000728 data/0009/000729 data/0009/000730 data/0009/000731 data/0009/000732 data/0009/000733 data/0009/000734 data/0009/000735 data/0009/000736 data/0009/000737 data/0009/000738 data/0009/000739 data/0009/000740 data/0009/000741 data/0009/000742 data/0009/000743 data/0009/000744 data/0009/000745 data/0009/000746 data/0009/000747 data/0009/000748 data/0009/000749 data/0009/000750 data/0009/000751 data/0009/000752 data/0009/000753 data/0009/000754 data/0009/000755 data/0009/000756 data/0009/000757 data/0009/000758 data/0009/000759 data/0009/000760 data/0009/000761 data/0009/000762 data/0009/000763 data/0009/000764 data/0009/000765 data/0009/000766 data/0009/000767 data/0009/000768 data/0009/000769 data/0009/000770 data/0009/000771 data/0009/000772 data/0009/000773 data/0009/000774 data/0009/000775 data/0009/000776 data/0009/000777 data/0009/000778 data/0009/000779 data/0009/000780 data/0009/000781 data/0009/000782 data/0009/000783 data/0009/000784 data/0009/000785 data/0009/000786 data/0009/000787 data/0009/000788 data/0009/000789 data/0009/000790 data/0009/000791 data/0009/000792 data/0009/000793 data/0009/000794 data/0009/000795 data/0009/000796 data/0009/000797 data/0009/000798 data/0009/000799 data/0009/000800 data/0009/000801 data/0009/000802 data/0009/000803 data/0009/000804 data/0009/000805 data/0009/000806 data/0009/000807 data/0009/000808 data/0009/000809 data/0009/000810 data/0009/000811 data/0009/000812 data/0009/000813 data/0009/000814 data/0009/000815 data/0009/000816 data/0009/000817 data/0009/000818 data/0009/000819 data/0009/000820 data/0009/000821 data/0009/000822 data/0009/000823 data/0009/000824 data/0009/000825 data/0009/000826 data/0009/000827 data/0009/000828 data/0009/000829 data/0009/000830 data/0009/000831 data/0009/000832 data/0009/000833 data/0009/000834 data/0009/000835 data/0009/000836 data/0009/000837 data/0009/000838 data/0009/000839 data/0009/000840 data/0009/000841 data/0009/000842 data/0009/000843 data/0009/000844 data/0009/000845 data/0009/000846 data/0009/000847 data/0009/000848 data/0009/000849 data/0009/000850 data/0009/000851 data/0009/000852 data/0009/000853 data/0009/000854 data/0009/000855 data/0009/000856 data/0009/000857 data/0009/000858 data/0009/000859 data/0009/000860 data/0009/000861 data/0009/000862 data/0009/000863 data/0009/000864 data/0009/000865 data/0009/000866 data/0009/000867 data/0009/000868 data/0009/000869 data/0009/000870 data/0009/000871 data/0009/000872 data/0009/000873 data/0009/000874 data/0009/000875 data/0009/000876 data/0009/000877 data/0009/000878 data/0009/000879 data/0009/000880 data/0009/000881 data/0009/000882 data/0009/000883 data/0009/000884 data/0009/000885 data/0009/000886 data/0009/000887 data/0009/000888 data/0009/000889 data/0009/000890 data/0009/000891 data/0009/000892 data/0009/000893 data/0009/000894 data/0009/000895 data/0009/000896 data/0009/000897 data/0009/000898 data/0009/000899 data/0009/000900 data/0009/000901 data/0009/000902 data/0009/000903 data/0009/000904 data/0009/000905 data/0009/000906 data/0009/000907 data/0009/000908 data/0009/000909 data/0009/000910 data/0009/000911 data/0009/000912 data/0009/000913 data/0009/000914 data/0009/000915 data/0009/000916 data/0009/000917 data/0009/000918 data/0009/000919 data/0009/000920 data/0009/000921 data/0009/000922 data/0009/000923 data/0009/000924 data/0009/000925 data/0009/000926 data/0009/000927 data/0009/000928 data/0009/000929 data/0009/000930 data/0009/000931 data/0009/000932 data/0009/000933 data/0009/000934 data/0009/000935 data/0009/000936 data/0009/000937 data/0009/000938 data/0012/000001 data/0012/000002 data/0012/000003 data/0012/000004 data/0012/000005 data/0012/000006 data/0012/000007 data/0012/000008 data/0012/000009 data/0012/000010 data/0012/000011 data/0012/000012 data/0012/000013 data/0012/000014 data/0012/000015 data/0012/000016 data/0012/000017 data/0012/000018 data/0012/000019 data/0012/000020 data/0012/000021 data/0012/000022 data/0012/000023 data/0012/000024 data/0012/000025 data/0012/000026 data/0012/000027 data/0012/000028 data/0012/000029 data/0012/000030 data/0012/000031 data/0012/000032 data/0012/000033 data/0012/000034 data/0012/000035 data/0012/000036 data/0012/000037 data/0012/000038 data/0012/000039 data/0012/000040 data/0012/000041 data/0012/000042 data/0012/000043 data/0012/000044 data/0012/000045 data/0012/000046 data/0012/000047 data/0012/000048 data/0012/000049 data/0012/000050 data/0012/000051 data/0012/000052 data/0012/000053 data/0012/000054 data/0012/000055 data/0012/000056 data/0012/000057 data/0012/000058 data/0012/000059 data/0012/000060 data/0012/000061 data/0012/000062 data/0012/000063 data/0012/000064 data/0012/000065 data/0012/000066 data/0012/000067 data/0012/000068 data/0012/000069 data/0012/000070 data/0012/000071 data/0012/000072 data/0012/000073 data/0012/000074 data/0012/000075 data/0012/000076 data/0012/000077 data/0012/000078 data/0012/000079 data/0012/000080 data/0012/000081 data/0012/000082 data/0012/000083 data/0012/000084 data/0012/000085 data/0012/000086 data/0012/000087 data/0012/000088 data/0012/000089 data/0012/000090 data/0012/000091 data/0012/000092 data/0012/000093 data/0012/000094 data/0012/000095 data/0012/000096 data/0012/000097 data/0012/000098 data/0012/000099 data/0012/000100 data/0012/000101 data/0012/000102 data/0012/000103 data/0012/000104 data/0012/000105 data/0012/000106 data/0012/000107 data/0012/000108 data/0012/000109 data/0012/000110 data/0012/000111 data/0012/000112 data/0012/000113 data/0012/000114 data/0012/000115 data/0012/000116 data/0012/000117 data/0012/000118 data/0012/000119 data/0012/000120 data/0012/000121 data/0012/000122 data/0012/000123 data/0012/000124 data/0012/000125 data/0012/000126 data/0012/000127 data/0012/000128 data/0012/000129 data/0012/000130 data/0012/000131 data/0012/000132 data/0012/000133 data/0012/000134 data/0012/000135 data/0012/000136 data/0012/000137 data/0012/000138 data/0012/000139 data/0012/000140 data/0012/000141 data/0012/000142 data/0012/000143 data/0012/000144 data/0012/000145 data/0012/000146 data/0012/000147 data/0012/000148 data/0012/000149 data/0012/000150 data/0012/000151 data/0012/000152 data/0012/000153 data/0012/000154 data/0012/000155 data/0012/000156 data/0012/000157 data/0012/000158 data/0012/000159 data/0012/000160 data/0012/000161 data/0012/000162 data/0012/000163 data/0012/000164 data/0012/000165 data/0012/000166 data/0012/000167 data/0012/000168 data/0012/000169 data/0012/000170 data/0012/000171 data/0012/000172 data/0012/000173 data/0012/000174 data/0012/000175 data/0012/000176 data/0012/000177 data/0012/000178 data/0012/000179 data/0012/000180 data/0012/000181 data/0012/000182 data/0012/000183 data/0012/000184 data/0012/000185 data/0012/000186 data/0012/000187 data/0012/000188 data/0012/000189 data/0012/000190 data/0012/000191 data/0012/000192 data/0012/000193 data/0012/000194 data/0012/000195 data/0012/000196 data/0012/000197 data/0012/000198 data/0012/000199 data/0012/000200 data/0012/000201 data/0012/000202 data/0012/000203 data/0012/000204 data/0012/000205 data/0012/000206 data/0012/000207 data/0012/000208 data/0012/000209 data/0012/000210 data/0012/000211 data/0012/000212 data/0012/000213 data/0012/000214 data/0012/000215 data/0012/000216 data/0012/000217 data/0012/000218 data/0012/000219 data/0012/000220 data/0012/000221 data/0012/000222 data/0012/000223 data/0012/000224 data/0012/000225 data/0012/000226 data/0012/000227 data/0012/000228 data/0012/000229 data/0012/000230 data/0012/000231 data/0012/000232 data/0012/000233 data/0012/000234 data/0012/000235 data/0012/000236 data/0012/000237 data/0012/000238 data/0012/000239 data/0012/000240 data/0012/000241 data/0012/000242 data/0012/000243 data/0012/000244 data/0012/000245 data/0012/000246 data/0012/000247 data/0012/000248 data/0012/000249 data/0012/000250 data/0012/000251 data/0012/000252 data/0012/000253 data/0012/000254 data/0012/000255 data/0012/000256 data/0012/000257 data/0012/000258 data/0012/000259 data/0012/000260 data/0012/000261 data/0012/000262 data/0012/000263 data/0012/000264 data/0012/000265 data/0012/000266 data/0012/000267 data/0012/000268 data/0012/000269 data/0012/000270 data/0012/000271 data/0012/000272 data/0012/000273 data/0012/000274 data/0012/000275 data/0012/000276 data/0012/000277 data/0012/000278 data/0012/000279 data/0012/000280 data/0012/000281 data/0012/000282 data/0012/000283 data/0012/000284 data/0012/000285 data/0012/000286 data/0012/000287 data/0012/000288 data/0012/000289 data/0012/000290 data/0012/000291 data/0012/000292 data/0012/000293 data/0012/000294 data/0012/000295 data/0012/000296 data/0012/000297 data/0012/000298 data/0012/000299 data/0012/000300 data/0012/000301 data/0012/000302 data/0012/000303 data/0012/000304 data/0012/000305 data/0012/000306 data/0012/000307 data/0012/000308 data/0012/000309 data/0012/000310 data/0012/000311 data/0012/000312 data/0012/000313 data/0012/000314 data/0012/000315 data/0012/000316 data/0012/000317 data/0012/000318 data/0012/000319 data/0012/000320 data/0012/000321 data/0012/000322 data/0012/000323 data/0012/000324 data/0012/000325 data/0012/000326 data/0012/000327 data/0012/000328 data/0012/000329 data/0012/000330 data/0012/000331 data/0012/000332 data/0012/000333 data/0012/000334 data/0012/000335 data/0012/000336 data/0012/000337 data/0012/000338 data/0012/000339 data/0012/000340 data/0012/000341 data/0012/000342 data/0012/000343 data/0012/000344 data/0012/000345 data/0012/000346 data/0012/000347 data/0012/000348 data/0012/000349 data/0012/000350 data/0012/000351 data/0012/000352 data/0012/000353 data/0012/000354 data/0012/000355 data/0012/000356 data/0012/000357 data/0012/000358 data/0012/000359 data/0012/000360 data/0012/000361 data/0012/000362 data/0012/000363 data/0012/000364 data/0012/000365 data/0012/000366 data/0012/000367 data/0012/000368 data/0012/000369 data/0012/000370 data/0012/000371 data/0012/000372 data/0012/000373 data/0012/000374 data/0012/000375 data/0012/000376 data/0012/000377 data/0012/000378 data/0012/000379 data/0012/000380 data/0012/000381 data/0012/000382 data/0012/000383 data/0012/000384 data/0012/000385 data/0012/000386 data/0012/000387 data/0012/000388 data/0012/000389 data/0012/000390 data/0012/000391 data/0012/000392 data/0012/000393 data/0012/000394 data/0012/000395 data/0012/000396 data/0012/000397 data/0012/000398 data/0012/000399 data/0012/000400 data/0012/000401 data/0012/000402 data/0012/000403 data/0012/000404 data/0012/000405 data/0012/000406 data/0012/000407 data/0012/000408 data/0012/000409 data/0012/000410 data/0012/000411 data/0012/000412 data/0012/000413 data/0012/000414 data/0012/000415 data/0012/000416 data/0012/000417 data/0012/000418 data/0012/000419 data/0012/000420 data/0012/000421 data/0012/000422 data/0012/000423 data/0012/000424 data/0012/000425 data/0012/000426 data/0012/000427 data/0012/000428 data/0012/000429 data/0012/000430 data/0012/000431 data/0012/000432 data/0012/000433 data/0012/000434 data/0012/000435 data/0012/000436 data/0012/000437 data/0012/000438 data/0012/000439 data/0012/000440 data/0012/000441 data/0012/000442 data/0012/000443 data/0012/000444 data/0012/000445 data/0012/000446 data/0012/000447 data/0012/000448 data/0012/000449 data/0012/000450 data/0012/000451 data/0012/000452 data/0012/000453 data/0012/000454 data/0012/000455 data/0012/000456 data/0012/000457 data/0012/000458 data/0012/000459 data/0012/000460 data/0012/000461 data/0012/000462 data/0012/000463 data/0012/000464 data/0012/000465 data/0012/000466 data/0012/000467 data/0012/000468 data/0012/000469 data/0012/000470 data/0012/000471 data/0012/000472 data/0012/000473 data/0012/000474 data/0012/000475 data/0012/000476 data/0012/000477 data/0012/000478 data/0012/000479 data/0012/000480 data/0012/000481 data/0012/000482 data/0012/000483 data/0012/000484 data/0012/000485 data/0012/000486 data/0012/000487 data/0012/000488 data/0012/000489 data/0012/000490 data/0012/000491 data/0012/000492 data/0012/000493 data/0012/000494 data/0012/000495 data/0012/000496 data/0012/000497 data/0012/000498 data/0012/000499 data/0012/000500 data/0012/000501 data/0012/000502 data/0012/000503 data/0012/000504 data/0012/000505 data/0012/000506 data/0012/000507 data/0012/000508 data/0012/000509 data/0012/000510 data/0012/000511 data/0012/000512 data/0012/000513 data/0012/000514 data/0012/000515 data/0012/000516 data/0012/000517 data/0012/000518 data/0012/000519 data/0012/000520 data/0012/000521 data/0012/000522 data/0012/000523 data/0012/000524 data/0012/000525 data/0012/000526 data/0012/000527 data/0012/000528 data/0012/000529 data/0012/000530 data/0012/000531 data/0012/000532 data/0012/000533 data/0012/000534 data/0012/000535 data/0012/000536 data/0012/000537 data/0012/000538 data/0012/000539 data/0012/000540 data/0012/000541 data/0012/000542 data/0012/000543 data/0012/000544 data/0012/000545 data/0012/000546 data/0012/000547 data/0012/000548 data/0012/000549 data/0012/000550 data/0012/000551 data/0012/000552 data/0012/000553 data/0012/000554 data/0012/000555 data/0012/000556 data/0012/000557 data/0012/000558 data/0012/000559 data/0012/000560 data/0012/000561 data/0012/000562 data/0012/000563 data/0012/000564 data/0012/000565 data/0012/000566 data/0012/000567 data/0012/000568 data/0012/000569 data/0012/000570 data/0012/000571 data/0012/000572 data/0012/000573 data/0012/000574 data/0012/000575 data/0012/000576 data/0012/000577 data/0012/000578 data/0012/000579 data/0012/000580 data/0012/000581 data/0012/000582 data/0012/000583 data/0012/000584 data/0012/000585 data/0012/000586 data/0012/000587 data/0012/000588 data/0012/000589 data/0012/000590 data/0012/000591 data/0012/000592 data/0012/000593 data/0012/000594 data/0012/000595 data/0012/000596 data/0012/000597 data/0012/000598 data/0012/000599 data/0012/000600 data/0012/000601 data/0012/000602 data/0012/000603 data/0012/000604 data/0012/000605 data/0012/000606 data/0012/000607 data/0012/000608 data/0012/000609 data/0012/000610 data/0012/000611 data/0012/000612 data/0012/000613 data/0012/000614 data/0012/000615 data/0012/000616 data/0012/000617 data/0012/000618 data/0012/000619 data/0012/000620 data/0012/000621 data/0012/000622 data/0012/000623 data/0012/000624 data/0012/000625 data/0012/000626 data/0012/000627 data/0012/000628 data/0012/000629 data/0012/000630 data/0012/000631 data/0012/000632 data/0012/000633 data/0012/000634 data/0012/000635 data/0012/000636 data/0012/000637 data/0012/000638 data/0012/000639 data/0012/000640 data/0012/000641 data/0012/000642 data/0012/000643 data/0012/000644 data/0012/000645 data/0012/000646 data/0012/000647 data/0012/000648 data/0012/000649 data/0012/000650 data/0012/000651 data/0012/000652 data/0012/000653 data/0012/000654 data/0012/000655 data/0012/000656 data/0012/000657 data/0012/000658 data/0012/000659 data/0012/000660 data/0012/000661 data/0012/000662 data/0012/000663 data/0012/000664 data/0012/000665 data/0012/000666 data/0012/000667 data/0012/000668 data/0012/000669 data/0012/000670 data/0012/000671 data/0012/000672 data/0012/000673 data/0012/000674 data/0012/000675 data/0012/000676 data/0012/000677 data/0012/000678 data/0012/000679 data/0012/000680 data/0012/000681 data/0012/000682 data/0012/000683 data/0012/000684 data/0012/000685 data/0012/000686 data/0012/000687 data/0012/000688 data/0012/000689 data/0012/000690 data/0012/000691 data/0012/000692 data/0012/000693 data/0012/000694 data/0012/000695 data/0012/000696 data/0012/000697 data/0012/000698 data/0012/000699 data/0012/000700 data/0012/000701 data/0012/000702 data/0012/000703 data/0012/000704 data/0012/000705 data/0012/000706 data/0012/000707 data/0012/000708 data/0012/000709 data/0012/000710 data/0012/000711 data/0012/000712 data/0012/000713 data/0012/000714 data/0012/000715 data/0012/000716 data/0012/000717 data/0012/000718 data/0012/000719 data/0012/000720 data/0012/000721 data/0012/000722 data/0012/000723 data/0012/000724 data/0012/000725 data/0012/000726 data/0012/000727 data/0012/000728 data/0012/000729 data/0012/000730 data/0012/000731 data/0012/000732 data/0012/000733 data/0012/000734 data/0012/000735 data/0012/000736 data/0012/000737 data/0012/000738 data/0012/000739 data/0012/000740 data/0012/000741 data/0012/000742 data/0012/000743 data/0012/000744 data/0012/000745 data/0012/000746 data/0012/000747 data/0012/000748 data/0012/000749 data/0012/000750 data/0012/000751 data/0012/000752 data/0012/000753 data/0012/000754 data/0012/000755 data/0012/000756 data/0012/000757 data/0012/000758 data/0012/000759 data/0012/000760 data/0012/000761 data/0012/000762 data/0012/000763 data/0012/000764 data/0012/000765 data/0012/000766 data/0012/000767 data/0012/000768 data/0012/000769 data/0012/000770 data/0012/000771 data/0012/000772 data/0012/000773 data/0012/000774 data/0012/000775 data/0012/000776 data/0012/000777 data/0012/000778 data/0012/000779 data/0012/000780 data/0012/000781 data/0012/000782 data/0012/000783 data/0012/000784 data/0012/000785 data/0012/000786 data/0012/000787 data/0012/000788 data/0012/000789 data/0012/000790 data/0012/000791 data/0012/000792 data/0012/000793 data/0012/000794 data/0012/000795 data/0012/000796 data/0012/000797 data/0012/000798 data/0012/000799 data/0012/000800 data/0012/000801 data/0012/000802 data/0012/000803 data/0012/000804 data/0012/000805 data/0012/000806 data/0012/000807 data/0012/000808 data/0012/000809 data/0012/000810 data/0012/000811 data/0012/000812 data/0012/000813 data/0012/000814 data/0012/000815 data/0012/000816 data/0012/000817 data/0012/000818 data/0012/000819 data/0012/000820 data/0012/000821 data/0012/000822 data/0012/000823 data/0012/000824 data/0012/000825 data/0012/000826 data/0012/000827 data/0012/000828 data/0012/000829 data/0012/000830 data/0012/000831 data/0012/000832 data/0012/000833 data/0012/000834 data/0012/000835 data/0012/000836 data/0012/000837 data/0012/000838 data/0012/000839 data/0012/000840 data/0012/000841 data/0012/000842 data/0012/000843 data/0012/000844 data/0012/000845 data/0012/000846 data/0012/000847 data/0012/000848 data/0012/000849 data/0012/000850 data/0012/000851 data/0012/000852 data/0012/000853 data/0012/000854 data/0012/000855 data/0012/000856 data/0012/000857 data/0012/000858 data/0012/000859 data/0012/000860 data/0012/000861 data/0012/000862 data/0012/000863 data/0012/000864 data/0012/000865 data/0012/000866 data/0012/000867 data/0012/000868 data/0012/000869 data/0013/000001 data/0013/000002 data/0013/000003 data/0013/000004 data/0013/000005 data/0013/000006 data/0013/000007 data/0013/000008 data/0013/000009 data/0013/000010 data/0013/000011 data/0013/000012 data/0013/000013 data/0013/000014 data/0013/000015 data/0013/000016 data/0013/000017 data/0013/000018 data/0013/000019 data/0013/000020 data/0013/000021 data/0013/000022 data/0013/000023 data/0013/000024 data/0013/000025 data/0013/000026 data/0013/000027 data/0013/000028 data/0013/000029 data/0013/000030 data/0013/000031 data/0013/000032 data/0013/000033 data/0013/000034 data/0013/000035 data/0013/000036 data/0013/000037 data/0013/000038 data/0013/000039 data/0013/000040 data/0013/000041 data/0013/000042 data/0013/000043 data/0013/000044 data/0013/000045 data/0013/000046 data/0013/000047 data/0013/000048 data/0013/000049 data/0013/000050 data/0013/000051 data/0013/000052 data/0013/000053 data/0013/000054 data/0013/000055 data/0013/000056 data/0013/000057 data/0013/000058 data/0013/000059 data/0013/000060 data/0013/000061 data/0013/000062 data/0013/000063 data/0013/000064 data/0013/000065 data/0013/000066 data/0013/000067 data/0013/000068 data/0013/000069 data/0013/000070 data/0013/000071 data/0013/000072 data/0013/000073 data/0013/000074 data/0013/000075 data/0013/000076 data/0013/000077 data/0013/000078 data/0013/000079 data/0013/000080 data/0013/000081 data/0013/000082 data/0013/000083 data/0013/000084 data/0013/000085 data/0013/000086 data/0013/000087 data/0013/000088 data/0013/000089 data/0013/000090 data/0013/000091 data/0013/000092 data/0013/000093 data/0013/000094 data/0013/000095 data/0013/000096 data/0013/000097 data/0013/000098 data/0013/000099 data/0013/000100 data/0013/000101 data/0013/000102 data/0013/000103 data/0013/000104 data/0013/000105 data/0013/000106 data/0013/000107 data/0013/000108 data/0013/000109 data/0013/000110 data/0013/000111 data/0013/000112 data/0013/000113 data/0013/000114 data/0013/000115 data/0013/000116 data/0013/000117 data/0013/000118 data/0013/000119 data/0013/000120 data/0013/000121 data/0013/000122 data/0013/000123 data/0013/000124 data/0013/000125 data/0013/000126 data/0013/000127 data/0013/000128 data/0013/000129 data/0013/000130 data/0013/000131 data/0013/000132 data/0013/000133 data/0013/000134 data/0013/000135 data/0013/000136 data/0013/000137 data/0013/000138 data/0013/000139 data/0013/000140 data/0013/000141 data/0013/000142 data/0013/000143 data/0013/000144 data/0013/000145 data/0013/000146 data/0013/000147 data/0013/000148 data/0013/000149 data/0013/000150 data/0013/000151 data/0013/000152 data/0013/000153 data/0013/000154 data/0013/000155 data/0013/000156 data/0013/000157 data/0013/000158 data/0013/000159 data/0013/000160 data/0013/000161 data/0013/000162 data/0013/000163 data/0013/000164 data/0013/000165 data/0013/000166 data/0013/000167 data/0013/000168 data/0013/000169 data/0013/000170 data/0013/000171 data/0013/000172 data/0013/000173 data/0013/000174 data/0013/000175 data/0013/000176 data/0013/000177 data/0013/000178 data/0013/000179 data/0013/000180 data/0013/000181 data/0013/000182 data/0013/000183 data/0013/000184 data/0013/000185 data/0013/000186 data/0013/000187 data/0013/000188 data/0013/000189 data/0013/000190 data/0013/000191 data/0013/000192 data/0013/000193 data/0013/000194 data/0013/000195 data/0013/000196 data/0013/000197 data/0013/000198 data/0013/000199 data/0013/000200 data/0013/000201 data/0013/000202 data/0013/000203 data/0013/000204 data/0013/000205 data/0013/000206 data/0013/000207 data/0013/000208 data/0013/000209 data/0013/000210 data/0013/000211 data/0013/000212 data/0013/000213 data/0013/000214 data/0013/000215 data/0013/000216 data/0013/000217 data/0013/000218 data/0013/000219 data/0013/000220 data/0013/000221 data/0013/000222 data/0013/000223 data/0013/000224 data/0013/000225 data/0013/000226 data/0013/000227 data/0013/000228 data/0013/000229 data/0013/000230 data/0013/000231 data/0013/000232 data/0013/000233 data/0013/000234 data/0013/000235 data/0013/000236 data/0013/000237 data/0013/000238 data/0013/000239 data/0013/000240 data/0013/000241 data/0013/000242 data/0013/000243 data/0013/000244 data/0013/000245 data/0013/000246 data/0013/000247 data/0013/000248 data/0013/000249 data/0013/000250 data/0013/000251 data/0013/000252 data/0013/000253 data/0013/000254 data/0013/000255 data/0013/000256 data/0013/000257 data/0013/000258 data/0013/000259 data/0013/000260 data/0013/000261 data/0013/000262 data/0013/000263 data/0013/000264 data/0013/000265 data/0013/000266 data/0013/000267 data/0013/000268 data/0013/000269 data/0013/000270 data/0013/000271 data/0013/000272 data/0013/000273 data/0013/000274 data/0013/000275 data/0013/000276 data/0013/000277 data/0013/000278 data/0013/000279 data/0013/000280 data/0013/000281 data/0013/000282 data/0013/000283 data/0013/000284 data/0013/000285 data/0013/000286 data/0013/000287 data/0013/000288 data/0013/000289 data/0013/000290 data/0013/000291 data/0013/000292 data/0013/000293 data/0013/000294 data/0013/000295 data/0013/000296 data/0013/000297 data/0013/000298 data/0013/000299 data/0013/000300 data/0013/000301 data/0013/000302 data/0013/000303 data/0013/000304 data/0013/000305 data/0013/000306 data/0013/000307 data/0013/000308 data/0013/000309 data/0013/000310 data/0013/000311 data/0013/000312 data/0013/000313 data/0013/000314 data/0013/000315 data/0013/000316 data/0013/000317 data/0013/000318 data/0013/000319 data/0013/000320 data/0013/000321 data/0013/000322 data/0013/000323 data/0013/000324 data/0013/000325 data/0013/000326 data/0013/000327 data/0013/000328 data/0013/000329 data/0013/000330 data/0013/000331 data/0013/000332 data/0013/000333 data/0013/000334 data/0013/000335 data/0013/000336 data/0013/000337 data/0013/000338 data/0013/000339 data/0013/000340 data/0013/000341 data/0013/000342 data/0013/000343 data/0013/000344 data/0013/000345 data/0013/000346 data/0013/000347 data/0013/000348 data/0013/000349 data/0013/000350 data/0013/000351 data/0013/000352 data/0013/000353 data/0013/000354 data/0013/000355 data/0013/000356 data/0013/000357 data/0013/000358 data/0013/000359 data/0013/000360 data/0013/000361 data/0013/000362 data/0013/000363 data/0013/000364 data/0013/000365 data/0013/000366 data/0013/000367 data/0013/000368 data/0013/000369 data/0013/000370 data/0013/000371 data/0013/000372 data/0013/000373 data/0013/000374 data/0013/000375 data/0013/000376 data/0013/000377 data/0013/000378 data/0013/000379 data/0013/000380 data/0013/000381 data/0013/000382 data/0013/000383 data/0013/000384 data/0013/000385 data/0013/000386 data/0013/000387 data/0013/000388 data/0013/000389 data/0013/000390 data/0013/000391 data/0013/000392 data/0013/000393 data/0013/000394 data/0013/000395 data/0013/000396 data/0013/000397 data/0013/000398 data/0013/000399 data/0013/000400 data/0013/000401 data/0013/000402 data/0013/000403 data/0013/000404 data/0013/000405 data/0013/000406 data/0013/000407 data/0013/000408 data/0013/000409 data/0013/000410 data/0013/000411 data/0013/000412 data/0013/000413 data/0013/000414 data/0013/000415 data/0013/000416 data/0013/000417 data/0013/000418 data/0013/000419 data/0013/000420 data/0013/000421 data/0013/000422 data/0013/000423 data/0013/000424 data/0013/000425 data/0013/000426 data/0013/000427 data/0013/000428 data/0013/000429 data/0013/000430 data/0013/000431 data/0013/000432 data/0013/000433 data/0013/000434 data/0013/000435 data/0013/000436 data/0013/000437 data/0013/000438 data/0013/000439 data/0013/000440 data/0013/000441 data/0013/000442 data/0013/000443 data/0013/000444 data/0013/000445 data/0013/000446 data/0013/000447 data/0013/000448 data/0013/000449 data/0013/000450 data/0013/000451 data/0013/000452 data/0013/000453 data/0013/000454 data/0013/000455 data/0013/000456 data/0013/000457 data/0013/000458 data/0013/000459 data/0013/000460 data/0013/000461 data/0013/000462 data/0013/000463 data/0013/000464 data/0013/000465 data/0013/000466 data/0013/000467 data/0013/000468 data/0013/000469 data/0013/000470 data/0013/000471 data/0013/000472 data/0013/000473 data/0013/000474 data/0013/000475 data/0013/000476 data/0013/000477 data/0013/000478 data/0013/000479 data/0013/000480 data/0013/000481 data/0013/000482 data/0013/000483 data/0013/000484 data/0013/000485 data/0013/000486 data/0013/000487 data/0013/000488 data/0013/000489 data/0013/000490 data/0013/000491 data/0013/000492 data/0013/000493 data/0013/000494 data/0013/000495 data/0013/000496 data/0013/000497 data/0013/000498 data/0013/000499 data/0013/000500 data/0013/000501 data/0013/000502 data/0013/000503 data/0013/000504 data/0013/000505 data/0013/000506 data/0013/000507 data/0013/000508 data/0013/000509 data/0013/000510 data/0013/000511 data/0013/000512 data/0013/000513 data/0013/000514 data/0013/000515 data/0013/000516 data/0013/000517 data/0013/000518 data/0013/000519 data/0013/000520 data/0013/000521 data/0013/000522 data/0013/000523 data/0013/000524 data/0013/000525 data/0013/000526 data/0013/000527 data/0013/000528 data/0013/000529 data/0013/000530 data/0013/000531 data/0013/000532 data/0013/000533 data/0013/000534 data/0013/000535 data/0013/000536 data/0013/000537 data/0013/000538 data/0013/000539 data/0013/000540 data/0013/000541 data/0013/000542 data/0013/000543 data/0013/000544 data/0013/000545 data/0013/000546 data/0013/000547 data/0013/000548 data/0013/000549 data/0013/000550 data/0013/000551 data/0013/000552 data/0013/000553 data/0013/000554 data/0013/000555 data/0013/000556 data/0013/000557 data/0013/000558 data/0013/000559 data/0013/000560 data/0013/000561 data/0013/000562 data/0013/000563 data/0013/000564 data/0013/000565 data/0013/000566 data/0013/000567 data/0013/000568 data/0013/000569 data/0013/000570 data/0013/000571 data/0013/000572 data/0013/000573 data/0013/000574 data/0013/000575 data/0013/000576 data/0013/000577 data/0013/000578 data/0013/000579 data/0013/000580 data/0013/000581 data/0013/000582 data/0013/000583 data/0013/000584 data/0013/000585 data/0013/000586 data/0013/000587 data/0013/000588 data/0013/000589 data/0013/000590 data/0013/000591 data/0013/000592 data/0013/000593 data/0013/000594 data/0013/000595 data/0013/000596 data/0013/000597 data/0013/000598 data/0013/000599 data/0013/000600 data/0013/000601 data/0013/000602 data/0013/000603 data/0013/000604 data/0013/000605 data/0013/000606 data/0013/000607 data/0013/000608 data/0013/000609 data/0013/000610 data/0013/000611 data/0013/000612 data/0013/000613 data/0013/000614 data/0013/000615 data/0013/000616 data/0013/000617 data/0013/000618 data/0013/000619 data/0013/000620 data/0013/000621 data/0013/000622 data/0013/000623 data/0013/000624 data/0013/000625 data/0013/000626 data/0013/000627 data/0013/000628 data/0013/000629 data/0013/000630 data/0013/000631 data/0013/000632 data/0013/000633 data/0013/000634 data/0013/000635 data/0013/000636 data/0013/000637 data/0013/000638 data/0013/000639 data/0013/000640 data/0013/000641 data/0013/000642 data/0013/000643 data/0013/000644 data/0013/000645 data/0013/000646 data/0013/000647 data/0013/000648 data/0013/000649 data/0013/000650 data/0013/000651 data/0013/000652 data/0013/000653 data/0013/000654 data/0013/000655 data/0013/000656 data/0013/000657 data/0013/000658 data/0013/000659 data/0013/000660 data/0013/000661 data/0013/000662 data/0013/000663 data/0013/000664 data/0013/000665 data/0013/000666 data/0013/000667 data/0013/000668 data/0013/000669 data/0013/000670 data/0013/000671 data/0013/000672 data/0013/000673 data/0013/000674 data/0013/000675 data/0013/000676 data/0013/000677 data/0013/000678 data/0013/000679 data/0013/000680 data/0013/000681 data/0013/000682 data/0013/000683 data/0013/000684 data/0013/000685 data/0013/000686 data/0013/000687 data/0013/000688 data/0013/000689 data/0013/000690 data/0013/000691 data/0013/000692 data/0013/000693 data/0013/000694 data/0013/000695 data/0013/000696 data/0013/000697 data/0013/000698 data/0013/000699 data/0013/000700 data/0013/000701 data/0013/000702 data/0013/000703 data/0013/000704 data/0013/000705 data/0013/000706 data/0013/000707 data/0013/000708 data/0013/000709 data/0013/000710 data/0013/000711 data/0013/000712 data/0013/000713 data/0013/000714 data/0013/000715 data/0013/000716 data/0013/000717 data/0013/000718 data/0013/000719 data/0013/000720 data/0013/000721 data/0013/000722 data/0013/000723 data/0013/000724 data/0013/000725 data/0013/000726 data/0013/000727 data/0013/000728 data/0013/000729 data/0013/000730 data/0013/000731 data/0013/000732 data/0013/000733 data/0013/000734 data/0013/000735 data/0013/000736 data/0013/000737 data/0013/000738 data/0013/000739 data/0013/000740 data/0013/000741 data/0013/000742 data/0013/000743 data/0013/000744 data/0013/000745 data/0013/000746 data/0013/000747 data/0013/000748 data/0013/000749 data/0013/000750 data/0013/000751 data/0013/000752 data/0013/000753 data/0013/000754 data/0013/000755 data/0013/000756 data/0013/000757 data/0013/000758 data/0013/000759 data/0013/000760 data/0013/000761 data/0013/000762 data/0013/000763 data/0013/000764 data/0013/000765 data/0013/000766 data/0013/000767 data/0013/000768 data/0013/000769 data/0013/000770 data/0013/000771 data/0013/000772 data/0013/000773 data/0013/000774 data/0013/000775 data/0013/000776 data/0013/000777 data/0013/000778 data/0013/000779 data/0013/000780 data/0013/000781 data/0013/000782 data/0013/000783 data/0013/000784 data/0013/000785 data/0013/000786 data/0013/000787 data/0013/000788 data/0013/000789 data/0013/000790 data/0013/000791 data/0013/000792 data/0013/000793 data/0013/000794 data/0013/000795 data/0013/000796 data/0013/000797 data/0013/000798 data/0013/000799 data/0013/000800 data/0013/000801 data/0013/000802 data/0013/000803 data/0013/000804 data/0013/000805 data/0013/000806 data/0013/000807 data/0013/000808 data/0013/000809 data/0013/000810 data/0013/000811 data/0013/000812 data/0013/000813 data/0013/000814 data/0013/000815 data/0013/000816 data/0013/000817 data/0013/000818 data/0013/000819 data/0013/000820 data/0013/000821 data/0013/000822 data/0013/000823 data/0013/000824 data/0013/000825 data/0013/000826 data/0013/000827 data/0013/000828 data/0013/000829 data/0013/000830 data/0013/000831 data/0013/000832 data/0013/000833 data/0013/000834 data/0013/000835 data/0013/000836 data/0013/000837 data/0013/000838 data/0013/000839 data/0013/000840 data/0013/000841 data/0013/000842 data/0013/000843 data/0013/000844 data/0013/000845 data/0013/000846 data/0013/000847 data/0013/000848 data/0013/000849 data/0013/000850 data/0013/000851 data/0013/000852 data/0013/000853 data/0013/000854 data/0013/000855 data/0013/000856 data/0013/000857 data/0013/000858 data/0013/000859 data/0013/000860 data/0013/000861 data/0013/000862 data/0013/000863 data/0013/000864 data/0013/000865 data/0013/000866 data/0013/000867 data/0013/000868 data/0013/000869 data/0013/000870 data/0013/000871 data/0013/000872 data/0013/000873 data/0013/000874 data/0013/000875 data/0013/000876 data/0013/000877 data/0013/000878 data/0013/000879 data/0013/000880 data/0013/000881 data/0013/000882 data/0013/000883 data/0013/000884 data/0013/000885 data/0013/000886 data/0013/000887 data/0013/000888 data/0013/000889 data/0013/000890 data/0013/000891 data/0013/000892 data/0013/000893 data/0013/000894 data/0013/000895 data/0013/000896 data/0013/000897 data/0013/000898 data/0013/000899 data/0013/000900 data/0013/000901 data/0013/000902 data/0013/000903 data/0013/000904 data/0013/000905 data/0013/000906 data/0013/000907 data/0013/000908 data/0013/000909 data/0013/000910 data/0013/000911 data/0013/000912 data/0013/000913 data/0013/000914 data/0013/000915 data/0013/000916 data/0013/000917 data/0013/000918 data/0013/000919 data/0013/000920 data/0013/000921 data/0013/000922 data/0013/000923 data/0013/000924 data/0013/000925 data/0013/000926 data/0013/000927 data/0013/000928 data/0013/000929 data/0013/000930 data/0013/000931 data/0013/000932 data/0013/000933 data/0013/000934 data/0013/000935 data/0013/000936 data/0013/000937 data/0013/000938 data/0013/000939 data/0013/000940 data/0013/000941 data/0013/000942 data/0013/000943 data/0013/000944 data/0013/000945 data/0013/000946 data/0013/000947 data/0013/000948 data/0013/000949 data/0013/000950 data/0013/000951 data/0013/000952 data/0013/000953 data/0013/000954 data/0013/000955 data/0013/000956 data/0013/000957 data/0013/000958 data/0013/000959 data/0013/000960 data/0013/000961 data/0013/000962 data/0013/000963 data/0013/000964 data/0013/000965 data/0013/000966 data/0013/000967 data/0013/000968 data/0013/000969 data/0013/000970 data/0013/000971 data/0013/000972 data/0013/000973 data/0013/000974 data/0013/000975 data/0013/000976 data/0013/000977 data/0013/000978 data/0013/000979 data/0013/000980 data/0013/000981 data/0013/000982 data/0013/000983 data/0013/000984 data/0013/000985 data/0013/000986 data/0013/000987 data/0013/000988 data/0013/000989 data/0013/000990 data/0013/000991 data/0013/000992 data/0013/000993 data/0013/000994 data/0013/000995 data/0013/000996 data/0013/000997 data/0013/000998 data/0013/000999 data/0013/001000 data/0013/001001 data/0013/001002 data/0013/001003 data/0013/001004 data/0013/001005 data/0013/001006 data/0013/001007 data/0013/001008 data/0013/001009 data/0013/001010 data/0013/001011 data/0013/001012 data/0013/001013 data/0013/001014 data/0013/001015 data/0013/001016 data/0013/001017 data/0013/001018 data/0013/001019 data/0013/001020 data/0013/001021 data/0013/001022 data/0013/001023 data/0013/001024 data/0013/001025 data/0013/001026 data/0013/001027 data/0013/001028 data/0013/001029 data/0013/001030 data/0013/001031 data/0013/001032 data/0013/001033 data/0013/001034 data/0013/001035 data/0013/001036 data/0013/001037 data/0013/001038 data/0013/001039 data/0013/001040 data/0013/001041 data/0013/001042 data/0013/001043 data/0013/001044 data/0013/001045 data/0013/001046 data/0013/001047 data/0013/001048 data/0013/001049 data/0013/001050 data/0013/001051 data/0013/001052 data/0013/001053 data/0013/001054 data/0013/001055 data/0013/001056 data/0013/001057 data/0013/001058 data/0013/001059 data/0013/001060 data/0013/001061 data/0013/001062 data/0013/001063 data/0013/001064 data/0013/001065 data/0013/001066 data/0013/001067 data/0013/001068 data/0013/001069 data/0013/001070 data/0013/001071 data/0013/001072 data/0013/001073 data/0013/001074 data/0013/001075 data/0013/001076 data/0013/001077 data/0013/001078 data/0013/001079 data/0013/001080 data/0013/001081 data/0013/001082 data/0013/001083 data/0013/001084 data/0013/001085 data/0013/001086 data/0013/001087 data/0013/001088 data/0013/001089 data/0013/001090 data/0013/001091 data/0013/001092 data/0013/001093 data/0013/001094 data/0013/001095 data/0013/001096 data/0013/001097 data/0013/001098 data/0013/001099 data/0013/001100 data/0013/001101 data/0013/001102 data/0013/001103 data/0014/000001 data/0014/000002 data/0014/000003 data/0014/000004 data/0014/000005 data/0014/000006 data/0014/000007 data/0014/000008 data/0014/000009 data/0014/000010 data/0014/000011 data/0014/000012 data/0014/000013 data/0014/000014 data/0014/000015 data/0014/000016 data/0014/000017 data/0014/000018 data/0014/000019 data/0014/000020 data/0014/000021 data/0014/000022 data/0014/000023 data/0014/000024 data/0014/000025 data/0014/000026 data/0014/000027 data/0014/000028 data/0014/000029 data/0014/000030 data/0014/000031 data/0014/000032 data/0014/000033 data/0014/000034 data/0014/000035 data/0014/000036 data/0014/000037 data/0014/000038 data/0014/000039 data/0014/000040 data/0014/000041 data/0014/000042 data/0014/000043 data/0014/000044 data/0014/000045 data/0014/000046 data/0014/000047 data/0014/000048 data/0014/000049 data/0014/000050 data/0014/000051 data/0014/000052 data/0014/000053 data/0014/000054 data/0014/000055 data/0014/000056 data/0014/000057 data/0014/000058 data/0014/000059 data/0014/000060 data/0014/000061 data/0014/000062 data/0014/000063 data/0014/000064 data/0014/000065 data/0014/000066 data/0014/000067 data/0014/000068 data/0014/000069 data/0014/000070 data/0014/000071 data/0014/000072 data/0014/000073 data/0014/000074 data/0014/000075 data/0014/000076 data/0014/000077 data/0014/000078 data/0014/000079 data/0014/000080 data/0014/000081 data/0014/000082 data/0014/000083 data/0014/000084 data/0014/000085 data/0014/000086 data/0014/000087 data/0014/000088 data/0014/000089 data/0014/000090 data/0014/000091 data/0014/000092 data/0014/000093 data/0014/000094 data/0014/000095 data/0014/000096 data/0014/000097 data/0014/000098 data/0014/000099 data/0014/000100 data/0014/000101 data/0014/000102 data/0014/000103 data/0014/000104 data/0014/000105 data/0014/000106 data/0014/000107 data/0014/000108 data/0014/000109 data/0014/000110 data/0014/000111 data/0014/000112 data/0014/000113 data/0014/000114 data/0014/000115 data/0014/000116 data/0014/000117 data/0014/000118 data/0014/000119 data/0014/000120 data/0014/000121 data/0014/000122 data/0014/000123 data/0014/000124 data/0014/000125 data/0014/000126 data/0014/000127 data/0014/000128 data/0014/000129 data/0014/000130 data/0014/000131 data/0014/000132 data/0014/000133 data/0014/000134 data/0014/000135 data/0014/000136 data/0014/000137 data/0014/000138 data/0014/000139 data/0014/000140 data/0014/000141 data/0014/000142 data/0014/000143 data/0014/000144 data/0014/000145 data/0014/000146 data/0014/000147 data/0014/000148 data/0014/000149 data/0014/000150 data/0014/000151 data/0014/000152 data/0014/000153 data/0014/000154 data/0014/000155 data/0014/000156 data/0014/000157 data/0014/000158 data/0014/000159 data/0014/000160 data/0014/000161 data/0014/000162 data/0014/000163 data/0014/000164 data/0014/000165 data/0014/000166 data/0014/000167 data/0014/000168 data/0014/000169 data/0014/000170 data/0014/000171 data/0014/000172 data/0014/000173 data/0014/000174 data/0014/000175 data/0014/000176 data/0014/000177 data/0014/000178 data/0014/000179 data/0014/000180 data/0014/000181 data/0014/000182 data/0014/000183 data/0014/000184 data/0014/000185 data/0014/000186 data/0014/000187 data/0014/000188 data/0014/000189 data/0014/000190 data/0014/000191 data/0014/000192 data/0014/000193 data/0014/000194 data/0014/000195 data/0014/000196 data/0014/000197 data/0014/000198 data/0014/000199 data/0014/000200 data/0014/000201 data/0014/000202 data/0014/000203 data/0014/000204 data/0014/000205 data/0014/000206 data/0014/000207 data/0014/000208 data/0014/000209 data/0014/000210 data/0014/000211 data/0014/000212 data/0014/000213 data/0014/000214 data/0014/000215 data/0014/000216 data/0014/000217 data/0014/000218 data/0014/000219 data/0014/000220 data/0014/000221 data/0014/000222 data/0014/000223 data/0014/000224 data/0014/000225 data/0014/000226 data/0014/000227 data/0014/000228 data/0014/000229 data/0014/000230 data/0014/000231 data/0014/000232 data/0014/000233 data/0014/000234 data/0014/000235 data/0014/000236 data/0014/000237 data/0014/000238 data/0014/000239 data/0014/000240 data/0014/000241 data/0014/000242 data/0014/000243 data/0014/000244 data/0014/000245 data/0014/000246 data/0014/000247 data/0014/000248 data/0014/000249 data/0014/000250 data/0014/000251 data/0014/000252 data/0014/000253 data/0014/000254 data/0014/000255 data/0014/000256 data/0014/000257 data/0014/000258 data/0014/000259 data/0014/000260 data/0014/000261 data/0014/000262 data/0014/000263 data/0014/000264 data/0014/000265 data/0014/000266 data/0014/000267 data/0014/000268 data/0014/000269 data/0014/000270 data/0014/000271 data/0014/000272 data/0014/000273 data/0014/000274 data/0014/000275 data/0014/000276 data/0014/000277 data/0014/000278 data/0014/000279 data/0014/000280 data/0014/000281 data/0014/000282 data/0014/000283 data/0014/000284 data/0014/000285 data/0014/000286 data/0014/000287 data/0014/000288 data/0014/000289 data/0014/000290 data/0014/000291 data/0014/000292 data/0014/000293 data/0014/000294 data/0014/000295 data/0014/000296 data/0014/000297 data/0014/000298 data/0014/000299 data/0014/000300 data/0014/000301 data/0014/000302 data/0014/000303 data/0014/000304 data/0014/000305 data/0014/000306 data/0014/000307 data/0014/000308 data/0014/000309 data/0014/000310 data/0014/000311 data/0014/000312 data/0014/000313 data/0014/000314 data/0014/000315 data/0014/000316 data/0014/000317 data/0014/000318 data/0014/000319 data/0014/000320 data/0014/000321 data/0014/000322 data/0014/000323 data/0014/000324 data/0014/000325 data/0014/000326 data/0014/000327 data/0014/000328 data/0014/000329 data/0014/000330 data/0014/000331 data/0014/000332 data/0014/000333 data/0014/000334 data/0014/000335 data/0014/000336 data/0014/000337 data/0014/000338 data/0014/000339 data/0014/000340 data/0014/000341 data/0014/000342 data/0014/000343 data/0014/000344 data/0014/000345 data/0014/000346 data/0014/000347 data/0014/000348 data/0014/000349 data/0014/000350 data/0014/000351 data/0014/000352 data/0014/000353 data/0014/000354 data/0014/000355 data/0014/000356 data/0014/000357 data/0014/000358 data/0014/000359 data/0014/000360 data/0014/000361 data/0014/000362 data/0014/000363 data/0014/000364 data/0014/000365 data/0014/000366 data/0014/000367 data/0014/000368 data/0014/000369 data/0014/000370 data/0014/000371 data/0014/000372 data/0014/000373 data/0014/000374 data/0014/000375 data/0014/000376 data/0014/000377 data/0014/000378 data/0014/000379 data/0014/000380 data/0014/000381 data/0014/000382 data/0014/000383 data/0014/000384 data/0014/000385 data/0014/000386 data/0014/000387 data/0014/000388 data/0014/000389 data/0014/000390 data/0014/000391 data/0014/000392 data/0014/000393 data/0014/000394 data/0014/000395 data/0014/000396 data/0014/000397 data/0014/000398 data/0014/000399 data/0014/000400 data/0014/000401 data/0014/000402 data/0014/000403 data/0014/000404 data/0014/000405 data/0014/000406 data/0014/000407 data/0014/000408 data/0014/000409 data/0014/000410 data/0014/000411 data/0014/000412 data/0014/000413 data/0014/000414 data/0014/000415 data/0014/000416 data/0014/000417 data/0014/000418 data/0014/000419 data/0014/000420 data/0014/000421 data/0014/000422 data/0014/000423 data/0014/000424 data/0014/000425 data/0014/000426 data/0014/000427 data/0014/000428 data/0014/000429 data/0014/000430 data/0014/000431 data/0014/000432 data/0014/000433 data/0014/000434 data/0014/000435 data/0014/000436 data/0014/000437 data/0014/000438 data/0014/000439 data/0014/000440 data/0014/000441 data/0014/000442 data/0014/000443 data/0014/000444 data/0014/000445 data/0014/000446 data/0014/000447 data/0014/000448 data/0014/000449 data/0014/000450 data/0014/000451 data/0014/000452 data/0014/000453 data/0014/000454 data/0014/000455 data/0014/000456 data/0014/000457 data/0014/000458 data/0014/000459 data/0014/000460 data/0014/000461 data/0014/000462 data/0014/000463 data/0014/000464 data/0014/000465 data/0014/000466 data/0014/000467 data/0014/000468 data/0014/000469 data/0014/000470 data/0014/000471 data/0014/000472 data/0014/000473 data/0014/000474 data/0014/000475 data/0014/000476 data/0014/000477 data/0014/000478 data/0014/000479 data/0014/000480 data/0014/000481 data/0014/000482 data/0014/000483 data/0014/000484 data/0014/000485 data/0014/000486 data/0014/000487 data/0014/000488 data/0014/000489 data/0014/000490 data/0014/000491 data/0014/000492 data/0014/000493 data/0014/000494 data/0014/000495 data/0014/000496 data/0014/000497 data/0014/000498 data/0014/000499 data/0014/000500 data/0014/000501 data/0014/000502 data/0014/000503 data/0014/000504 data/0014/000505 data/0014/000506 data/0014/000507 data/0014/000508 data/0014/000509 data/0014/000510 data/0014/000511 data/0014/000512 data/0014/000513 data/0014/000514 data/0014/000515 data/0014/000516 data/0014/000517 data/0014/000518 data/0014/000519 data/0014/000520 data/0014/000521 data/0014/000522 data/0014/000523 data/0014/000524 data/0014/000525 data/0014/000526 data/0014/000527 data/0014/000528 data/0014/000529 data/0014/000530 data/0014/000531 data/0014/000532 data/0014/000533 data/0014/000534 data/0014/000535 data/0014/000536 data/0014/000537 data/0014/000538 data/0014/000539 data/0014/000540 data/0014/000541 data/0014/000542 data/0014/000543 data/0014/000544 data/0014/000545 data/0014/000546 data/0014/000547 data/0014/000548 data/0014/000549 data/0014/000550 data/0014/000551 data/0014/000552 data/0014/000553 data/0014/000554 data/0014/000555 data/0014/000556 data/0014/000557 data/0014/000558 data/0014/000559 data/0014/000560 data/0014/000561 data/0014/000562 data/0014/000563 data/0014/000564 data/0014/000565 data/0014/000566 data/0014/000567 data/0014/000568 data/0014/000569 data/0014/000570 data/0014/000571 data/0014/000572 data/0014/000573 data/0014/000574 data/0014/000575 data/0014/000576 data/0014/000577 data/0014/000578 data/0014/000579 data/0014/000580 data/0014/000581 data/0014/000582 data/0014/000583 data/0014/000584 data/0014/000585 data/0014/000586 data/0014/000587 data/0014/000588 data/0014/000589 data/0014/000590 data/0014/000591 data/0014/000592 data/0014/000593 data/0014/000594 data/0014/000595 data/0014/000596 data/0014/000597 data/0014/000598 data/0014/000599 data/0014/000600 data/0014/000601 data/0014/000602 data/0014/000603 data/0014/000604 data/0014/000605 data/0014/000606 data/0014/000607 data/0014/000608 data/0014/000609 data/0014/000610 data/0014/000611 data/0014/000612 data/0014/000613 data/0014/000614 data/0014/000615 data/0014/000616 data/0014/000617 data/0014/000618 data/0014/000619 data/0014/000620 data/0014/000621 data/0014/000622 data/0014/000623 data/0014/000624 data/0014/000625 data/0014/000626 data/0014/000627 data/0014/000628 data/0014/000629 data/0014/000630 data/0014/000631 data/0014/000632 data/0014/000633 data/0014/000634 data/0014/000635 data/0014/000636 data/0014/000637 data/0014/000638 data/0014/000639 data/0014/000640 data/0014/000641 data/0014/000642 data/0014/000643 data/0014/000644 data/0014/000645 data/0014/000646 data/0014/000647 data/0014/000648 data/0014/000649 data/0014/000650 data/0014/000651 data/0014/000652 data/0014/000653 data/0014/000654 data/0014/000655 data/0014/000656 data/0014/000657 data/0014/000658 data/0014/000659 data/0014/000660 data/0014/000661 data/0014/000662 data/0014/000663 data/0014/000664 data/0014/000665 data/0014/000666 data/0014/000667 data/0014/000668 data/0014/000669 data/0014/000670 data/0014/000671 data/0014/000672 data/0014/000673 data/0014/000674 data/0014/000675 data/0014/000676 data/0014/000677 data/0014/000678 data/0014/000679 data/0014/000680 data/0014/000681 data/0014/000682 data/0014/000683 data/0014/000684 data/0014/000685 data/0014/000686 data/0014/000687 data/0014/000688 data/0014/000689 data/0014/000690 data/0014/000691 data/0014/000692 data/0014/000693 data/0014/000694 data/0014/000695 data/0014/000696 data/0014/000697 data/0014/000698 data/0014/000699 data/0014/000700 data/0014/000701 data/0014/000702 data/0014/000703 data/0014/000704 data/0014/000705 data/0014/000706 data/0014/000707 data/0014/000708 data/0014/000709 data/0014/000710 data/0014/000711 data/0014/000712 data/0014/000713 data/0014/000714 data/0014/000715 data/0014/000716 data/0014/000717 data/0014/000718 data/0014/000719 data/0014/000720 data/0014/000721 data/0014/000722 data/0014/000723 data/0014/000724 data/0014/000725 data/0014/000726 data/0014/000727 data/0014/000728 data/0014/000729 data/0014/000730 data/0014/000731 data/0014/000732 data/0014/000733 data/0014/000734 data/0014/000735 data/0014/000736 data/0014/000737 data/0014/000738 data/0014/000739 data/0014/000740 data/0014/000741 data/0014/000742 data/0014/000743 data/0014/000744 data/0014/000745 data/0014/000746 data/0014/000747 data/0014/000748 data/0014/000749 data/0014/000750 data/0014/000751 data/0014/000752 data/0014/000753 data/0014/000754 data/0014/000755 data/0014/000756 data/0014/000757 data/0014/000758 data/0014/000759 data/0014/000760 data/0014/000761 data/0014/000762 data/0014/000763 data/0014/000764 data/0014/000765 data/0014/000766 data/0014/000767 data/0014/000768 data/0014/000769 data/0014/000770 data/0014/000771 data/0014/000772 data/0014/000773 data/0014/000774 data/0014/000775 data/0014/000776 data/0014/000777 data/0014/000778 data/0014/000779 data/0014/000780 data/0014/000781 data/0014/000782 data/0014/000783 data/0014/000784 data/0014/000785 data/0014/000786 data/0014/000787 data/0014/000788 data/0014/000789 data/0014/000790 data/0014/000791 data/0014/000792 data/0014/000793 data/0014/000794 data/0014/000795 data/0014/000796 data/0014/000797 data/0014/000798 data/0014/000799 data/0014/000800 data/0014/000801 data/0014/000802 data/0014/000803 data/0014/000804 data/0014/000805 data/0014/000806 data/0014/000807 data/0014/000808 data/0014/000809 data/0014/000810 data/0014/000811 data/0014/000812 data/0014/000813 data/0014/000814 data/0014/000815 data/0014/000816 data/0014/000817 data/0014/000818 data/0014/000819 data/0014/000820 data/0014/000821 data/0014/000822 data/0014/000823 data/0014/000824 data/0014/000825 data/0014/000826 data/0014/000827 data/0014/000828 data/0014/000829 data/0014/000830 data/0014/000831 data/0014/000832 data/0014/000833 data/0014/000834 data/0014/000835 data/0014/000836 data/0014/000837 data/0014/000838 data/0014/000839 data/0014/000840 data/0014/000841 data/0014/000842 data/0014/000843 data/0014/000844 data/0014/000845 data/0014/000846 data/0014/000847 data/0014/000848 data/0014/000849 data/0014/000850 data/0014/000851 data/0014/000852 data/0014/000853 data/0014/000854 data/0014/000855 data/0014/000856 data/0014/000857 data/0014/000858 data/0014/000859 data/0014/000860 data/0014/000861 data/0014/000862 data/0014/000863 data/0014/000864 data/0014/000865 data/0014/000866 data/0014/000867 data/0014/000868 data/0014/000869 data/0014/000870 data/0014/000871 data/0014/000872 data/0014/000873 data/0014/000874 data/0014/000875 data/0014/000876 data/0014/000877 data/0014/000878 data/0014/000879 data/0014/000880 data/0014/000881 data/0014/000882 data/0014/000883 data/0014/000884 data/0014/000885 data/0014/000886 data/0014/000887 data/0014/000888 data/0014/000889 data/0014/000890 data/0014/000891 data/0014/000892 data/0014/000893 data/0014/000894 data/0014/000895 data/0014/000896 data/0014/000897 data/0014/000898 data/0014/000899 data/0014/000900 data/0014/000901 data/0014/000902 data/0014/000903 data/0014/000904 data/0014/000905 data/0014/000906 data/0014/000907 data/0014/000908 data/0014/000909 data/0014/000910 data/0014/000911 data/0014/000912 data/0014/000913 data/0014/000914 data/0014/000915 data/0014/000916 data/0014/000917 data/0014/000918 data/0014/000919 data/0014/000920 data/0014/000921 data/0014/000922 data/0014/000923 data/0014/000924 data/0014/000925 data/0014/000926 data/0014/000927 data/0014/000928 data/0014/000929 data/0014/000930 data/0014/000931 data/0014/000932 data/0014/000933 data/0014/000934 data/0014/000935 data/0014/000936 data/0014/000937 data/0014/000938 data/0014/000939 data/0014/000940 data/0014/000941 data/0014/000942 data/0014/000943 data/0014/000944 data/0014/000945 data/0014/000946 data/0014/000947 data/0014/000948 data/0014/000949 data/0014/000950 data/0014/000951 data/0014/000952 data/0014/000953 data/0014/000954 data/0014/000955 data/0014/000956 data/0014/000957 data/0014/000958 data/0014/000959 data/0014/000960 data/0014/000961 data/0014/000962 data/0014/000963 data/0014/000964 data/0014/000965 data/0014/000966 data/0014/000967 data/0014/000968 data/0014/000969 data/0014/000970 data/0014/000971 data/0014/000972 data/0014/000973 data/0014/000974 data/0014/000975 data/0014/000976 data/0014/000977 data/0014/000978 data/0014/000979 data/0014/000980 data/0014/000981 data/0014/000982 data/0014/000983 data/0014/000984 data/0014/000985 data/0014/000986 data/0014/000987 data/0014/000988 data/0014/000989 data/0014/000990 data/0014/000991 data/0014/000992 data/0014/000993 data/0014/000994 data/0014/000995 data/0014/000996 data/0014/000997 data/0014/000998 data/0014/000999 data/0014/001000 data/0014/001001 data/0014/001002 data/0014/001003 data/0014/001004 data/0014/001005 data/0014/001006 data/0014/001007 data/0014/001008 data/0014/001009 data/0014/001010 data/0014/001011 data/0014/001012 data/0014/001013 data/0014/001014 data/0014/001015 data/0014/001016 data/0014/001017 data/0014/001018 data/0014/001019 data/0014/001020 data/0014/001021 data/0014/001022 data/0014/001023 data/0014/001024 data/0014/001025 data/0014/001026 data/0014/001027 data/0014/001028 data/0014/001029 data/0014/001030 data/0014/001031 data/0014/001032 data/0014/001033 data/0014/001034 data/0014/001035 data/0014/001036 data/0014/001037 data/0014/001038 data/0014/001039 data/0014/001040 data/0014/001041 data/0014/001042 data/0014/001043 data/0014/001044 data/0014/001045 data/0014/001046 data/0014/001047 data/0014/001048 data/0014/001049 data/0014/001050 data/0014/001051 data/0014/001052 data/0014/001053 data/0014/001054 data/0014/001055 data/0014/001056 data/0014/001057 data/0014/001058 data/0014/001059 data/0014/001060 data/0014/001061 data/0014/001062 data/0014/001063 data/0014/001064 data/0015/000001 data/0015/000002 data/0015/000003 data/0015/000004 data/0015/000005 data/0015/000006 data/0015/000007 data/0015/000008 data/0015/000009 data/0015/000010 data/0015/000011 data/0015/000012 data/0015/000013 data/0015/000014 data/0015/000015 data/0015/000016 data/0015/000017 data/0015/000018 data/0015/000019 data/0015/000020 data/0015/000021 data/0015/000022 data/0015/000023 data/0015/000024 data/0015/000025 data/0015/000026 data/0015/000027 data/0015/000028 data/0015/000029 data/0015/000030 data/0015/000031 data/0015/000032 data/0015/000033 data/0015/000034 data/0015/000035 data/0015/000036 data/0015/000037 data/0015/000038 data/0015/000039 data/0015/000040 data/0015/000041 data/0015/000042 data/0015/000043 data/0015/000044 data/0015/000045 data/0015/000046 data/0015/000047 data/0015/000048 data/0015/000049 data/0015/000050 data/0015/000051 data/0015/000052 data/0015/000053 data/0015/000054 data/0015/000055 data/0015/000056 data/0015/000057 data/0015/000058 data/0015/000059 data/0015/000060 data/0015/000061 data/0015/000062 data/0015/000063 data/0015/000064 data/0015/000065 data/0015/000066 data/0015/000067 data/0015/000068 data/0015/000069 data/0015/000070 data/0015/000071 data/0015/000072 data/0015/000073 data/0015/000074 data/0015/000075 data/0015/000076 data/0015/000077 data/0015/000078 data/0015/000079 data/0015/000080 data/0015/000081 data/0015/000082 data/0015/000083 data/0015/000084 data/0015/000085 data/0015/000086 data/0015/000087 data/0015/000088 data/0015/000089 data/0015/000090 data/0015/000091 data/0015/000092 data/0015/000093 data/0015/000094 data/0015/000095 data/0015/000096 data/0015/000097 data/0015/000098 data/0015/000099 data/0015/000100 data/0015/000101 data/0015/000102 data/0015/000103 data/0015/000104 data/0015/000105 data/0015/000106 data/0015/000107 data/0015/000108 data/0015/000109 data/0015/000110 data/0015/000111 data/0015/000112 data/0015/000113 data/0015/000114 data/0015/000115 data/0015/000116 data/0015/000117 data/0015/000118 data/0015/000119 data/0015/000120 data/0015/000121 data/0015/000122 data/0015/000123 data/0015/000124 data/0015/000125 data/0015/000126 data/0015/000127 data/0015/000128 data/0015/000129 data/0015/000130 data/0015/000131 data/0015/000132 data/0015/000133 data/0015/000134 data/0015/000135 data/0015/000136 data/0015/000137 data/0015/000138 data/0015/000139 data/0015/000140 data/0015/000141 data/0015/000142 data/0015/000143 data/0015/000144 data/0015/000145 data/0015/000146 data/0015/000147 data/0015/000148 data/0015/000149 data/0015/000150 data/0015/000151 data/0015/000152 data/0015/000153 data/0015/000154 data/0015/000155 data/0015/000156 data/0015/000157 data/0015/000158 data/0015/000159 data/0015/000160 data/0015/000161 data/0015/000162 data/0015/000163 data/0015/000164 data/0015/000165 data/0015/000166 data/0015/000167 data/0015/000168 data/0015/000169 data/0015/000170 data/0015/000171 data/0015/000172 data/0015/000173 data/0015/000174 data/0015/000175 data/0015/000176 data/0015/000177 data/0015/000178 data/0015/000179 data/0015/000180 data/0015/000181 data/0015/000182 data/0015/000183 data/0015/000184 data/0015/000185 data/0015/000186 data/0015/000187 data/0015/000188 data/0015/000189 data/0015/000190 data/0015/000191 data/0015/000192 data/0015/000193 data/0015/000194 data/0015/000195 data/0015/000196 data/0015/000197 data/0015/000198 data/0015/000199 data/0015/000200 data/0015/000201 data/0015/000202 data/0015/000203 data/0015/000204 data/0015/000205 data/0015/000206 data/0015/000207 data/0015/000208 data/0015/000209 data/0015/000210 data/0015/000211 data/0015/000212 data/0015/000213 data/0015/000214 data/0015/000215 data/0015/000216 data/0015/000217 data/0015/000218 data/0015/000219 data/0015/000220 data/0015/000221 data/0015/000222 data/0015/000223 data/0015/000224 data/0015/000225 data/0015/000226 data/0015/000227 data/0015/000228 data/0015/000229 data/0015/000230 data/0015/000231 data/0015/000232 data/0015/000233 data/0015/000234 data/0015/000235 data/0015/000236 data/0015/000237 data/0015/000238 data/0015/000239 data/0015/000240 data/0015/000241 data/0015/000242 data/0015/000243 data/0015/000244 data/0015/000245 data/0015/000246 data/0015/000247 data/0015/000248 data/0015/000249 data/0015/000250 data/0015/000251 data/0015/000252 data/0015/000253 data/0015/000254 data/0015/000255 data/0015/000256 data/0015/000257 data/0015/000258 data/0015/000259 data/0015/000260 data/0015/000261 data/0015/000262 data/0015/000263 data/0015/000264 data/0015/000265 data/0015/000266 data/0015/000267 data/0015/000268 data/0015/000269 data/0015/000270 data/0015/000271 data/0015/000272 data/0015/000273 data/0015/000274 data/0015/000275 data/0015/000276 data/0015/000277 data/0015/000278 data/0015/000279 data/0015/000280 data/0015/000281 data/0015/000282 data/0015/000283 data/0015/000284 data/0015/000285 data/0015/000286 data/0015/000287 data/0015/000288 data/0015/000289 data/0015/000290 data/0015/000291 data/0015/000292 data/0015/000293 data/0015/000294 data/0015/000295 data/0015/000296 data/0015/000297 data/0015/000298 data/0015/000299 data/0015/000300 data/0015/000301 data/0015/000302 data/0015/000303 data/0015/000304 data/0015/000305 data/0015/000306 data/0015/000307 data/0015/000308 data/0015/000309 data/0015/000310 data/0015/000311 data/0015/000312 data/0015/000313 data/0015/000314 data/0015/000315 data/0015/000316 data/0015/000317 data/0015/000318 data/0015/000319 data/0015/000320 data/0015/000321 data/0015/000322 data/0015/000323 data/0015/000324 data/0015/000325 data/0015/000326 data/0015/000327 data/0015/000328 data/0015/000329 data/0015/000330 data/0015/000331 data/0015/000332 data/0015/000333 data/0015/000334 data/0015/000335 data/0015/000336 data/0015/000337 data/0015/000338 data/0015/000339 data/0015/000340 data/0015/000341 data/0015/000342 data/0015/000343 data/0015/000344 data/0015/000345 data/0015/000346 data/0015/000347 data/0015/000348 data/0015/000349 data/0015/000350 data/0015/000351 data/0015/000352 data/0015/000353 data/0015/000354 data/0015/000355 data/0015/000356 data/0015/000357 data/0015/000358 data/0015/000359 data/0015/000360 data/0015/000361 data/0015/000362 data/0015/000363 data/0015/000364 data/0015/000365 data/0015/000366 data/0015/000367 data/0015/000368 data/0015/000369 data/0015/000370 data/0015/000371 data/0015/000372 data/0015/000373 data/0015/000374 data/0015/000375 data/0015/000376 data/0015/000377 data/0015/000378 data/0015/000379 data/0015/000380 data/0015/000381 data/0015/000382 data/0015/000383 data/0015/000384 data/0015/000385 data/0015/000386 data/0015/000387 data/0015/000388 data/0015/000389 data/0015/000390 data/0015/000391 data/0015/000392 data/0015/000393 data/0015/000394 data/0015/000395 data/0015/000396 data/0015/000397 data/0015/000398 data/0015/000399 data/0015/000400 data/0015/000401 data/0015/000402 data/0015/000403 data/0015/000404 data/0015/000405 data/0015/000406 data/0015/000407 data/0015/000408 data/0015/000409 data/0015/000410 data/0015/000411 data/0015/000412 data/0015/000413 data/0015/000414 data/0015/000415 data/0015/000416 data/0015/000417 data/0015/000418 data/0015/000419 data/0015/000420 data/0015/000421 data/0015/000422 data/0015/000423 data/0015/000424 data/0015/000425 data/0015/000426 data/0015/000427 data/0015/000428 data/0015/000429 data/0015/000430 data/0015/000431 data/0015/000432 data/0015/000433 data/0015/000434 data/0015/000435 data/0015/000436 data/0015/000437 data/0015/000438 data/0015/000439 data/0015/000440 data/0015/000441 data/0015/000442 data/0015/000443 data/0015/000444 data/0015/000445 data/0015/000446 data/0015/000447 data/0015/000448 data/0015/000449 data/0015/000450 data/0015/000451 data/0015/000452 data/0015/000453 data/0015/000454 data/0015/000455 data/0015/000456 data/0015/000457 data/0015/000458 data/0015/000459 data/0015/000460 data/0015/000461 data/0015/000462 data/0015/000463 data/0015/000464 data/0015/000465 data/0015/000466 data/0015/000467 data/0015/000468 data/0015/000469 data/0015/000470 data/0015/000471 data/0015/000472 data/0015/000473 data/0015/000474 data/0015/000475 data/0015/000476 data/0015/000477 data/0015/000478 data/0015/000479 data/0015/000480 data/0015/000481 data/0015/000482 data/0015/000483 data/0015/000484 data/0015/000485 data/0015/000486 data/0015/000487 data/0015/000488 data/0015/000489 data/0015/000490 data/0015/000491 data/0015/000492 data/0015/000493 data/0015/000494 data/0015/000495 data/0015/000496 data/0015/000497 data/0015/000498 data/0015/000499 data/0015/000500 data/0015/000501 data/0015/000502 data/0015/000503 data/0015/000504 data/0015/000505 data/0015/000506 data/0015/000507 data/0015/000508 data/0015/000509 data/0015/000510 data/0015/000511 data/0015/000512 data/0015/000513 data/0015/000514 data/0015/000515 data/0015/000516 data/0015/000517 data/0015/000518 data/0015/000519 data/0015/000520 data/0015/000521 data/0015/000522 data/0015/000523 data/0015/000524 data/0015/000525 data/0015/000526 data/0015/000527 data/0015/000528 data/0015/000529 data/0015/000530 data/0015/000531 data/0015/000532 data/0015/000533 data/0015/000534 data/0015/000535 data/0015/000536 data/0015/000537 data/0015/000538 data/0015/000539 data/0015/000540 data/0015/000541 data/0015/000542 data/0015/000543 data/0015/000544 data/0015/000545 data/0015/000546 data/0015/000547 data/0015/000548 data/0015/000549 data/0015/000550 data/0015/000551 data/0015/000552 data/0015/000553 data/0015/000554 data/0015/000555 data/0015/000556 data/0015/000557 data/0015/000558 data/0015/000559 data/0015/000560 data/0015/000561 data/0015/000562 data/0015/000563 data/0015/000564 data/0015/000565 data/0015/000566 data/0015/000567 data/0015/000568 data/0015/000569 data/0015/000570 data/0015/000571 data/0015/000572 data/0015/000573 data/0015/000574 data/0015/000575 data/0015/000576 data/0015/000577 data/0015/000578 data/0015/000579 data/0015/000580 data/0015/000581 data/0015/000582 data/0015/000583 data/0015/000584 data/0015/000585 data/0015/000586 data/0015/000587 data/0015/000588 data/0015/000589 data/0015/000590 data/0015/000591 data/0015/000592 data/0015/000593 data/0015/000594 data/0015/000595 data/0015/000596 data/0015/000597 data/0015/000598 data/0015/000599 data/0015/000600 data/0015/000601 data/0015/000602 data/0015/000603 data/0015/000604 data/0015/000605 data/0015/000606 data/0015/000607 data/0015/000608 data/0015/000609 data/0015/000610 data/0015/000611 data/0015/000612 data/0015/000613 data/0015/000614 data/0015/000615 data/0015/000616 data/0015/000617 data/0015/000618 data/0015/000619 data/0015/000620 data/0015/000621 data/0015/000622 data/0015/000623 data/0015/000624 data/0015/000625 data/0015/000626 data/0015/000627 data/0015/000628 data/0015/000629 data/0015/000630 data/0015/000631 data/0015/000632 data/0015/000633 data/0015/000634 data/0015/000635 data/0015/000636 data/0015/000637 data/0015/000638 data/0015/000639 data/0015/000640 data/0015/000641 data/0015/000642 data/0015/000643 data/0015/000644 data/0015/000645 data/0015/000646 data/0015/000647 data/0015/000648 data/0015/000649 data/0015/000650 data/0015/000651 data/0015/000652 data/0015/000653 data/0015/000654 data/0015/000655 data/0015/000656 data/0015/000657 data/0015/000658 data/0015/000659 data/0015/000660 data/0015/000661 data/0015/000662 data/0015/000663 data/0015/000664 data/0015/000665 data/0015/000666 data/0015/000667 data/0015/000668 data/0015/000669 data/0015/000670 data/0015/000671 data/0015/000672 data/0015/000673 data/0015/000674 data/0015/000675 data/0015/000676 data/0015/000677 data/0015/000678 data/0015/000679 data/0015/000680 data/0015/000681 data/0015/000682 data/0015/000683 data/0015/000684 data/0015/000685 data/0015/000686 data/0015/000687 data/0015/000688 data/0015/000689 data/0015/000690 data/0015/000691 data/0015/000692 data/0015/000693 data/0015/000694 data/0015/000695 data/0015/000696 data/0015/000697 data/0015/000698 data/0015/000699 data/0015/000700 data/0015/000701 data/0015/000702 data/0015/000703 data/0015/000704 data/0015/000705 data/0015/000706 data/0015/000707 data/0015/000708 data/0015/000709 data/0015/000710 data/0015/000711 data/0015/000712 data/0015/000713 data/0015/000714 data/0015/000715 data/0015/000716 data/0015/000717 data/0015/000718 data/0015/000719 data/0015/000720 data/0015/000721 data/0015/000722 data/0015/000723 data/0015/000724 data/0015/000725 data/0015/000726 data/0015/000727 data/0015/000728 data/0015/000729 data/0015/000730 data/0015/000731 data/0015/000732 data/0015/000733 data/0015/000734 data/0015/000735 data/0015/000736 data/0015/000737 data/0015/000738 data/0015/000739 data/0015/000740 data/0015/000741 data/0015/000742 data/0015/000743 data/0015/000744 data/0015/000745 data/0015/000746 data/0015/000747 data/0015/000748 data/0015/000749 data/0015/000750 data/0015/000751 data/0015/000752 data/0015/000753 data/0015/000754 data/0015/000755 data/0015/000756 data/0015/000757 data/0015/000758 data/0015/000759 data/0015/000760 data/0015/000761 data/0015/000762 data/0015/000763 data/0015/000764 data/0015/000765 data/0015/000766 data/0015/000767 data/0015/000768 data/0015/000769 data/0015/000770 data/0015/000771 data/0015/000772 data/0015/000773 data/0015/000774 data/0015/000775 data/0015/000776 data/0015/000777 data/0015/000778 data/0015/000779 data/0015/000780 data/0015/000781 data/0015/000782 data/0015/000783 data/0015/000784 data/0015/000785 data/0015/000786 data/0015/000787 data/0015/000788 data/0015/000789 data/0015/000790 data/0015/000791 data/0015/000792 data/0015/000793 data/0015/000794 data/0015/000795 data/0015/000796 data/0015/000797 data/0015/000798 data/0015/000799 data/0015/000800 data/0015/000801 data/0015/000802 data/0015/000803 data/0015/000804 data/0015/000805 data/0015/000806 data/0015/000807 data/0015/000808 data/0015/000809 data/0015/000810 data/0015/000811 data/0015/000812 data/0015/000813 data/0015/000814 data/0015/000815 data/0015/000816 data/0015/000817 data/0015/000818 data/0015/000819 data/0015/000820 data/0015/000821 data/0015/000822 data/0015/000823 data/0015/000824 data/0015/000825 data/0015/000826 data/0015/000827 data/0015/000828 data/0015/000829 data/0015/000830 data/0015/000831 data/0015/000832 data/0015/000833 data/0015/000834 data/0015/000835 data/0015/000836 data/0015/000837 data/0015/000838 data/0015/000839 data/0015/000840 data/0015/000841 data/0015/000842 data/0015/000843 data/0015/000844 data/0015/000845 data/0015/000846 data/0015/000847 data/0015/000848 data/0015/000849 data/0015/000850 data/0015/000851 data/0015/000852 data/0015/000853 data/0015/000854 data/0015/000855 data/0015/000856 data/0015/000857 data/0015/000858 data/0015/000859 data/0015/000860 data/0015/000861 data/0015/000862 data/0015/000863 data/0015/000864 data/0015/000865 data/0015/000866 data/0015/000867 data/0015/000868 data/0015/000869 data/0015/000870 data/0015/000871 data/0015/000872 data/0015/000873 data/0015/000874 data/0015/000875 data/0015/000876 data/0015/000877 data/0015/000878 data/0015/000879 data/0015/000880 data/0015/000881 data/0015/000882 data/0015/000883 data/0015/000884 data/0015/000885 data/0015/000886 data/0015/000887 data/0015/000888 data/0015/000889 data/0015/000890 data/0015/000891 data/0015/000892 data/0015/000893 data/0015/000894 data/0015/000895 data/0015/000896 data/0015/000897 data/0015/000898 data/0015/000899 data/0015/000900 data/0015/000901 data/0015/000902 data/0015/000903 data/0015/000904 data/0015/000905 data/0015/000906 data/0015/000907 data/0015/000908 data/0015/000909 data/0015/000910 data/0015/000911 data/0015/000912 data/0015/000913 data/0015/000914 data/0015/000915 data/0015/000916 data/0015/000917 data/0015/000918 data/0015/000919 data/0015/000920 data/0015/000921 data/0015/000922 data/0015/000923 data/0015/000924 data/0015/000925 data/0015/000926 data/0015/000927 data/0015/000928 data/0015/000929 data/0015/000930 data/0015/000931 data/0015/000932 data/0015/000933 data/0015/000934 data/0015/000935 data/0015/000936 data/0015/000937 data/0015/000938 data/0015/000939 data/0015/000940 data/0015/000941 data/0015/000942 data/0015/000943 data/0015/000944 data/0015/000945 data/0015/000946 data/0015/000947 data/0015/000948 data/0015/000949 data/0015/000950 data/0015/000951 data/0015/000952 data/0015/000953 data/0015/000954 data/0015/000955 data/0015/000956 data/0015/000957 data/0015/000958 data/0015/000959 data/0015/000960 data/0015/000961 data/0015/000962 data/0015/000963 data/0015/000964 data/0015/000965 data/0016/000001 data/0016/000002 data/0016/000003 data/0016/000004 data/0016/000005 data/0016/000006 data/0016/000007 data/0016/000008 data/0016/000009 data/0016/000010 data/0016/000011 data/0016/000012 data/0016/000013 data/0016/000014 data/0016/000015 data/0016/000016 data/0016/000017 data/0016/000018 data/0016/000019 data/0016/000020 data/0016/000021 data/0016/000022 data/0016/000023 data/0016/000024 data/0016/000025 data/0016/000026 data/0016/000027 data/0016/000028 data/0016/000029 data/0016/000030 data/0016/000031 data/0016/000032 data/0016/000033 data/0016/000034 data/0016/000035 data/0016/000036 data/0016/000037 data/0016/000038 data/0016/000039 data/0016/000040 data/0016/000041 data/0016/000042 data/0016/000043 data/0016/000044 data/0016/000045 data/0016/000046 data/0016/000047 data/0016/000048 data/0016/000049 data/0016/000050 data/0016/000051 data/0016/000052 data/0016/000053 data/0016/000054 data/0016/000055 data/0016/000056 data/0016/000057 data/0016/000058 data/0016/000059 data/0016/000060 data/0016/000061 data/0016/000062 data/0016/000063 data/0016/000064 data/0016/000065 data/0016/000066 data/0016/000067 data/0016/000068 data/0016/000069 data/0016/000070 data/0016/000071 data/0016/000072 data/0016/000073 data/0016/000074 data/0016/000075 data/0016/000076 data/0016/000077 data/0016/000078 data/0016/000079 data/0016/000080 data/0016/000081 data/0016/000082 data/0016/000083 data/0016/000084 data/0016/000085 data/0016/000086 data/0016/000087 data/0016/000088 data/0016/000089 data/0016/000090 data/0016/000091 data/0016/000092 data/0016/000093 data/0016/000094 data/0016/000095 data/0016/000096 data/0016/000097 data/0016/000098 data/0016/000099 data/0016/000100 data/0016/000101 data/0016/000102 data/0016/000103 data/0016/000104 data/0016/000105 data/0016/000106 data/0016/000107 data/0016/000108 data/0016/000109 data/0016/000110 data/0016/000111 data/0016/000112 data/0016/000113 data/0016/000114 data/0016/000115 data/0016/000116 data/0016/000117 data/0016/000118 data/0016/000119 data/0016/000120 data/0016/000121 data/0016/000122 data/0016/000123 data/0016/000124 data/0016/000125 data/0016/000126 data/0016/000127 data/0016/000128 data/0016/000129 data/0016/000130 data/0016/000131 data/0016/000132 data/0016/000133 data/0016/000134 data/0016/000135 data/0016/000136 data/0016/000137 data/0016/000138 data/0016/000139 data/0016/000140 data/0016/000141 data/0016/000142 data/0016/000143 data/0016/000144 data/0016/000145 data/0016/000146 data/0016/000147 data/0016/000148 data/0016/000149 data/0016/000150 data/0016/000151 data/0016/000152 data/0016/000153 data/0016/000154 data/0016/000155 data/0016/000156 data/0016/000157 data/0016/000158 data/0016/000159 data/0016/000160 data/0016/000161 data/0016/000162 data/0016/000163 data/0016/000164 data/0016/000165 data/0016/000166 data/0016/000167 data/0016/000168 data/0016/000169 data/0016/000170 data/0016/000171 data/0016/000172 data/0016/000173 data/0016/000174 data/0016/000175 data/0016/000176 data/0016/000177 data/0016/000178 data/0016/000179 data/0016/000180 data/0016/000181 data/0016/000182 data/0016/000183 data/0016/000184 data/0016/000185 data/0016/000186 data/0016/000187 data/0016/000188 data/0016/000189 data/0016/000190 data/0016/000191 data/0016/000192 data/0016/000193 data/0016/000194 data/0016/000195 data/0016/000196 data/0016/000197 data/0016/000198 data/0016/000199 data/0016/000200 data/0016/000201 data/0016/000202 data/0016/000203 data/0016/000204 data/0016/000205 data/0016/000206 data/0016/000207 data/0016/000208 data/0016/000209 data/0016/000210 data/0016/000211 data/0016/000212 data/0016/000213 data/0016/000214 data/0016/000215 data/0016/000216 data/0016/000217 data/0016/000218 data/0016/000219 data/0016/000220 data/0016/000221 data/0016/000222 data/0016/000223 data/0016/000224 data/0016/000225 data/0016/000226 data/0016/000227 data/0016/000228 data/0016/000229 data/0016/000230 data/0016/000231 data/0016/000232 data/0016/000233 data/0016/000234 data/0016/000235 data/0016/000236 data/0016/000237 data/0016/000238 data/0016/000239 data/0016/000240 data/0016/000241 data/0016/000242 data/0016/000243 data/0016/000244 data/0016/000245 data/0016/000246 data/0016/000247 data/0016/000248 data/0016/000249 data/0016/000250 data/0016/000251 data/0016/000252 data/0016/000253 data/0016/000254 data/0016/000255 data/0016/000256 data/0016/000257 data/0016/000258 data/0016/000259 data/0016/000260 data/0016/000261 data/0016/000262 data/0016/000263 data/0016/000264 data/0016/000265 data/0016/000266 data/0016/000267 data/0016/000268 data/0016/000269 data/0016/000270 data/0016/000271 data/0016/000272 data/0016/000273 data/0016/000274 data/0016/000275 data/0016/000276 data/0016/000277 data/0016/000278 data/0016/000279 data/0016/000280 data/0016/000281 data/0016/000282 data/0016/000283 data/0016/000284 data/0016/000285 data/0016/000286 data/0016/000287 data/0016/000288 data/0016/000289 data/0016/000290 data/0016/000291 data/0016/000292 data/0016/000293 data/0016/000294 data/0016/000295 data/0016/000296 data/0016/000297 data/0016/000298 data/0016/000299 data/0016/000300 data/0016/000301 data/0016/000302 data/0016/000303 data/0016/000304 data/0016/000305 data/0016/000306 data/0016/000307 data/0016/000308 data/0016/000309 data/0016/000310 data/0016/000311 data/0016/000312 data/0016/000313 data/0016/000314 data/0016/000315 data/0016/000316 data/0016/000317 data/0016/000318 data/0016/000319 data/0016/000320 data/0016/000321 data/0016/000322 data/0016/000323 data/0016/000324 data/0016/000325 data/0016/000326 data/0016/000327 data/0016/000328 data/0016/000329 data/0016/000330 data/0016/000331 data/0016/000332 data/0016/000333 data/0016/000334 data/0016/000335 data/0016/000336 data/0016/000337 data/0016/000338 data/0016/000339 data/0016/000340 data/0016/000341 data/0016/000342 data/0016/000343 data/0016/000344 data/0016/000345 data/0016/000346 data/0016/000347 data/0016/000348 data/0016/000349 data/0016/000350 data/0016/000351 data/0016/000352 data/0016/000353 data/0016/000354 data/0016/000355 data/0016/000356 data/0016/000357 data/0016/000358 data/0016/000359 data/0016/000360 data/0016/000361 data/0016/000362 data/0016/000363 data/0016/000364 data/0016/000365 data/0016/000366 data/0016/000367 data/0016/000368 data/0016/000369 data/0016/000370 data/0016/000371 data/0016/000372 data/0016/000373 data/0016/000374 data/0016/000375 data/0016/000376 data/0016/000377 data/0016/000378 data/0016/000379 data/0016/000380 data/0016/000381 data/0016/000382 data/0016/000383 data/0016/000384 data/0016/000385 data/0016/000386 data/0016/000387 data/0016/000388 data/0016/000389 data/0016/000390 data/0016/000391 data/0016/000392 data/0016/000393 data/0016/000394 data/0016/000395 data/0016/000396 data/0016/000397 data/0016/000398 data/0016/000399 data/0016/000400 data/0016/000401 data/0016/000402 data/0016/000403 data/0016/000404 data/0016/000405 data/0016/000406 data/0016/000407 data/0016/000408 data/0016/000409 data/0016/000410 data/0016/000411 data/0016/000412 data/0016/000413 data/0016/000414 data/0016/000415 data/0016/000416 data/0016/000417 data/0016/000418 data/0016/000419 data/0016/000420 data/0016/000421 data/0016/000422 data/0016/000423 data/0016/000424 data/0016/000425 data/0016/000426 data/0016/000427 data/0016/000428 data/0016/000429 data/0016/000430 data/0016/000431 data/0016/000432 data/0016/000433 data/0016/000434 data/0016/000435 data/0016/000436 data/0016/000437 data/0016/000438 data/0016/000439 data/0016/000440 data/0016/000441 data/0016/000442 data/0016/000443 data/0016/000444 data/0016/000445 data/0016/000446 data/0016/000447 data/0016/000448 data/0016/000449 data/0016/000450 data/0016/000451 data/0016/000452 data/0016/000453 data/0016/000454 data/0016/000455 data/0016/000456 data/0016/000457 data/0016/000458 data/0016/000459 data/0016/000460 data/0016/000461 data/0016/000462 data/0016/000463 data/0016/000464 data/0016/000465 data/0016/000466 data/0016/000467 data/0016/000468 data/0016/000469 data/0016/000470 data/0016/000471 data/0016/000472 data/0016/000473 data/0016/000474 data/0016/000475 data/0016/000476 data/0016/000477 data/0016/000478 data/0016/000479 data/0016/000480 data/0016/000481 data/0016/000482 data/0016/000483 data/0016/000484 data/0016/000485 data/0016/000486 data/0016/000487 data/0016/000488 data/0016/000489 data/0016/000490 data/0016/000491 data/0016/000492 data/0016/000493 data/0016/000494 data/0016/000495 data/0016/000496 data/0016/000497 data/0016/000498 data/0016/000499 data/0016/000500 data/0016/000501 data/0016/000502 data/0016/000503 data/0016/000504 data/0016/000505 data/0016/000506 data/0016/000507 data/0016/000508 data/0016/000509 data/0016/000510 data/0016/000511 data/0016/000512 data/0016/000513 data/0016/000514 data/0016/000515 data/0016/000516 data/0016/000517 data/0016/000518 data/0016/000519 data/0016/000520 data/0016/000521 data/0016/000522 data/0016/000523 data/0016/000524 data/0016/000525 data/0016/000526 data/0016/000527 data/0016/000528 data/0016/000529 data/0016/000530 data/0016/000531 data/0016/000532 data/0016/000533 data/0016/000534 data/0016/000535 data/0016/000536 data/0016/000537 data/0016/000538 data/0016/000539 data/0016/000540 data/0016/000541 data/0016/000542 data/0016/000543 data/0016/000544 data/0016/000545 data/0016/000546 data/0016/000547 data/0016/000548 data/0016/000549 data/0016/000550 data/0016/000551 data/0016/000552 data/0016/000553 data/0016/000554 data/0016/000555 data/0016/000556 data/0016/000557 data/0016/000558 data/0016/000559 data/0016/000560 data/0016/000561 data/0016/000562 data/0016/000563 data/0016/000564 data/0016/000565 data/0016/000566 data/0016/000567 data/0016/000568 data/0016/000569 data/0016/000570 data/0016/000571 data/0016/000572 data/0016/000573 data/0016/000574 data/0016/000575 data/0016/000576 data/0016/000577 data/0016/000578 data/0016/000579 data/0016/000580 data/0016/000581 data/0016/000582 data/0016/000583 data/0016/000584 data/0016/000585 data/0016/000586 data/0016/000587 data/0016/000588 data/0016/000589 data/0016/000590 data/0016/000591 data/0016/000592 data/0016/000593 data/0016/000594 data/0016/000595 data/0016/000596 data/0016/000597 data/0016/000598 data/0016/000599 data/0016/000600 data/0016/000601 data/0016/000602 data/0016/000603 data/0016/000604 data/0016/000605 data/0016/000606 data/0016/000607 data/0016/000608 data/0016/000609 data/0016/000610 data/0016/000611 data/0016/000612 data/0016/000613 data/0016/000614 data/0016/000615 data/0016/000616 data/0016/000617 data/0016/000618 data/0016/000619 data/0016/000620 data/0016/000621 data/0016/000622 data/0016/000623 data/0016/000624 data/0016/000625 data/0016/000626 data/0016/000627 data/0016/000628 data/0016/000629 data/0016/000630 data/0016/000631 data/0016/000632 data/0016/000633 data/0016/000634 data/0016/000635 data/0016/000636 data/0016/000637 data/0016/000638 data/0016/000639 data/0016/000640 data/0016/000641 data/0016/000642 data/0016/000643 data/0016/000644 data/0016/000645 data/0016/000646 data/0016/000647 data/0016/000648 data/0016/000649 data/0016/000650 data/0016/000651 data/0016/000652 data/0016/000653 data/0016/000654 data/0016/000655 data/0016/000656 data/0016/000657 data/0016/000658 data/0016/000659 data/0016/000660 data/0016/000661 data/0016/000662 data/0016/000663 data/0016/000664 data/0016/000665 data/0016/000666 data/0016/000667 data/0016/000668 data/0016/000669 data/0016/000670 data/0016/000671 data/0016/000672 data/0016/000673 data/0016/000674 data/0016/000675 data/0016/000676 data/0016/000677 data/0016/000678 data/0016/000679 data/0016/000680 data/0016/000681 data/0016/000682 data/0016/000683 data/0016/000684 data/0016/000685 data/0016/000686 data/0016/000687 data/0016/000688 data/0016/000689 data/0016/000690 data/0016/000691 data/0016/000692 data/0016/000693 data/0016/000694 data/0016/000695 data/0016/000696 data/0016/000697 data/0016/000698 data/0016/000699 data/0016/000700 data/0016/000701 data/0016/000702 data/0016/000703 data/0016/000704 data/0016/000705 data/0016/000706 data/0016/000707 data/0016/000708 data/0016/000709 data/0016/000710 data/0016/000711 data/0016/000712 data/0016/000713 data/0016/000714 data/0016/000715 data/0016/000716 data/0016/000717 data/0016/000718 data/0016/000719 data/0016/000720 data/0016/000721 data/0016/000722 data/0016/000723 data/0016/000724 data/0016/000725 data/0016/000726 data/0016/000727 data/0016/000728 data/0016/000729 data/0016/000730 data/0016/000731 data/0016/000732 data/0016/000733 data/0016/000734 data/0016/000735 data/0016/000736 data/0016/000737 data/0016/000738 data/0016/000739 data/0016/000740 data/0016/000741 data/0016/000742 data/0016/000743 data/0016/000744 data/0016/000745 data/0016/000746 data/0016/000747 data/0016/000748 data/0016/000749 data/0016/000750 data/0016/000751 data/0016/000752 data/0016/000753 data/0016/000754 data/0016/000755 data/0016/000756 data/0016/000757 data/0016/000758 data/0016/000759 data/0016/000760 data/0016/000761 data/0016/000762 data/0016/000763 data/0016/000764 data/0016/000765 data/0016/000766 data/0016/000767 data/0016/000768 data/0016/000769 data/0016/000770 data/0016/000771 data/0016/000772 data/0016/000773 data/0016/000774 data/0016/000775 data/0016/000776 data/0016/000777 data/0016/000778 data/0016/000779 data/0016/000780 data/0016/000781 data/0016/000782 data/0016/000783 data/0016/000784 data/0016/000785 data/0016/000786 data/0016/000787 data/0016/000788 data/0016/000789 data/0016/000790 data/0016/000791 data/0016/000792 data/0016/000793 data/0016/000794 data/0016/000795 data/0016/000796 data/0016/000797 data/0016/000798 data/0016/000799 data/0016/000800 data/0016/000801 data/0016/000802 data/0016/000803 data/0016/000804 data/0016/000805 data/0016/000806 data/0016/000807 data/0016/000808 data/0016/000809 data/0016/000810 data/0016/000811 data/0016/000812 data/0016/000813 data/0016/000814 data/0016/000815 data/0016/000816 data/0016/000817 data/0016/000818 data/0016/000819 data/0016/000820 data/0016/000821 data/0016/000822 data/0016/000823 data/0016/000824 data/0016/000825 data/0016/000826 data/0016/000827 data/0016/000828 data/0016/000829 data/0016/000830 data/0016/000831 data/0016/000832 data/0016/000833 data/0016/000834 data/0016/000835 data/0016/000836 data/0016/000837 data/0016/000838 data/0016/000839 data/0016/000840 data/0016/000841 data/0016/000842 data/0016/000843 data/0016/000844 data/0016/000845 data/0016/000846 data/0016/000847 data/0016/000848 data/0016/000849 data/0016/000850 data/0016/000851 data/0016/000852 data/0016/000853 data/0016/000854 data/0016/000855 data/0016/000856 data/0016/000857 data/0016/000858 data/0016/000859 data/0016/000860 data/0016/000861 data/0016/000862 data/0016/000863 data/0016/000864 data/0016/000865 data/0016/000866 data/0016/000867 data/0016/000868 data/0016/000869 data/0016/000870 data/0016/000871 data/0016/000872 data/0016/000873 data/0016/000874 data/0016/000875 data/0016/000876 data/0016/000877 data/0016/000878 data/0016/000879 data/0016/000880 data/0016/000881 data/0016/000882 data/0016/000883 data/0016/000884 data/0016/000885 data/0016/000886 data/0016/000887 data/0016/000888 data/0016/000889 data/0016/000890 data/0016/000891 data/0016/000892 data/0016/000893 data/0016/000894 data/0016/000895 data/0016/000896 data/0016/000897 data/0016/000898 data/0016/000899 data/0016/000900 data/0016/000901 data/0016/000902 data/0016/000903 data/0016/000904 data/0016/000905 data/0016/000906 data/0016/000907 data/0016/000908 data/0016/000909 data/0016/000910 data/0016/000911 data/0016/000912 data/0016/000913 data/0016/000914 data/0016/000915 data/0016/000916 data/0016/000917 data/0016/000918 data/0016/000919 data/0016/000920 data/0016/000921 data/0016/000922 data/0016/000923 data/0016/000924 data/0016/000925 data/0016/000926 data/0016/000927 data/0016/000928 data/0016/000929 data/0016/000930 data/0016/000931 data/0016/000932 data/0016/000933 data/0016/000934 data/0016/000935 data/0016/000936 data/0016/000937 data/0016/000938 data/0016/000939 data/0016/000940 data/0016/000941 data/0016/000942 data/0016/000943 data/0016/000944 data/0016/000945 data/0016/000946 data/0016/000947 data/0016/000948 data/0016/000949 data/0016/000950 data/0016/000951 data/0016/000952 data/0016/000953 data/0016/000954 data/0016/000955 data/0016/000956 data/0016/000957 data/0016/000958 data/0016/000959 data/0016/000960 data/0016/000961 data/0016/000962 data/0016/000963 data/0016/000964 data/0016/000965 data/0016/000966 data/0016/000967 data/0016/000968 data/0016/000969 data/0016/000970 data/0016/000971 data/0016/000972 data/0016/000973 data/0016/000974 data/0016/000975 data/0016/000976 data/0016/000977 data/0016/000978 data/0016/000979 data/0016/000980 data/0016/000981 data/0016/000982 data/0016/000983 data/0016/000984 data/0016/000985 data/0016/000986 data/0016/000987 data/0016/000988 data/0016/000989 data/0016/000990 data/0016/000991 data/0016/000992 data/0016/000993 data/0016/000994 data/0016/000995 data/0016/000996 data/0016/000997 data/0016/000998 data/0016/000999 data/0016/001000 data/0016/001001 data/0019/000001 data/0019/000002 data/0019/000003 data/0019/000004 data/0019/000005 data/0019/000006 data/0019/000007 data/0019/000008 data/0019/000009 data/0019/000010 data/0019/000011 data/0019/000012 data/0019/000013 data/0019/000014 data/0019/000015 data/0019/000016 data/0019/000017 data/0019/000018 data/0019/000019 data/0019/000020 data/0019/000021 data/0019/000022 data/0019/000023 data/0019/000024 data/0019/000025 data/0019/000026 data/0019/000027 data/0019/000028 data/0019/000029 data/0019/000030 data/0019/000031 data/0019/000032 data/0019/000033 data/0019/000034 data/0019/000035 data/0019/000036 data/0019/000037 data/0019/000038 data/0019/000039 data/0019/000040 data/0019/000041 data/0019/000042 data/0019/000043 data/0019/000044 data/0019/000045 data/0019/000046 data/0019/000047 data/0019/000048 data/0019/000049 data/0019/000050 data/0019/000051 data/0019/000052 data/0019/000053 data/0019/000054 data/0019/000055 data/0019/000056 data/0019/000057 data/0019/000058 data/0019/000059 data/0019/000060 data/0019/000061 data/0019/000062 data/0019/000063 data/0019/000064 data/0019/000065 data/0019/000066 data/0019/000067 data/0019/000068 data/0019/000069 data/0019/000070 data/0019/000071 data/0019/000072 data/0019/000073 data/0019/000074 data/0019/000075 data/0019/000076 data/0019/000077 data/0019/000078 data/0019/000079 data/0019/000080 data/0019/000081 data/0019/000082 data/0019/000083 data/0019/000084 data/0019/000085 data/0019/000086 data/0019/000087 data/0019/000088 data/0019/000089 data/0019/000090 data/0019/000091 data/0019/000092 data/0019/000093 data/0019/000094 data/0019/000095 data/0019/000096 data/0019/000097 data/0019/000098 data/0019/000099 data/0019/000100 data/0019/000101 data/0019/000102 data/0019/000103 data/0019/000104 data/0019/000105 data/0019/000106 data/0019/000107 data/0019/000108 data/0019/000109 data/0019/000110 data/0019/000111 data/0019/000112 data/0019/000113 data/0019/000114 data/0019/000115 data/0019/000116 data/0019/000117 data/0019/000118 data/0019/000119 data/0019/000120 data/0019/000121 data/0019/000122 data/0019/000123 data/0019/000124 data/0019/000125 data/0019/000126 data/0019/000127 data/0019/000128 data/0019/000129 data/0019/000130 data/0019/000131 data/0019/000132 data/0019/000133 data/0019/000134 data/0019/000135 data/0019/000136 data/0019/000137 data/0019/000138 data/0019/000139 data/0019/000140 data/0019/000141 data/0019/000142 data/0019/000143 data/0019/000144 data/0019/000145 data/0019/000146 data/0019/000147 data/0019/000148 data/0019/000149 data/0019/000150 data/0019/000151 data/0019/000152 data/0019/000153 data/0019/000154 data/0019/000155 data/0019/000156 data/0019/000157 data/0019/000158 data/0019/000159 data/0019/000160 data/0019/000161 data/0019/000162 data/0019/000163 data/0019/000164 data/0019/000165 data/0019/000166 data/0019/000167 data/0019/000168 data/0019/000169 data/0019/000170 data/0019/000171 data/0019/000172 data/0019/000173 data/0019/000174 data/0019/000175 data/0019/000176 data/0019/000177 data/0019/000178 data/0019/000179 data/0019/000180 data/0019/000181 data/0019/000182 data/0019/000183 data/0019/000184 data/0019/000185 data/0019/000186 data/0019/000187 data/0019/000188 data/0019/000189 data/0019/000190 data/0019/000191 data/0019/000192 data/0019/000193 data/0019/000194 data/0019/000195 data/0019/000196 data/0019/000197 data/0019/000198 data/0019/000199 data/0019/000200 data/0019/000201 data/0019/000202 data/0019/000203 data/0019/000204 data/0019/000205 data/0019/000206 data/0019/000207 data/0019/000208 data/0019/000209 data/0019/000210 data/0019/000211 data/0019/000212 data/0019/000213 data/0019/000214 data/0019/000215 data/0019/000216 data/0019/000217 data/0019/000218 data/0019/000219 data/0019/000220 data/0019/000221 data/0019/000222 data/0019/000223 data/0019/000224 data/0019/000225 data/0019/000226 data/0019/000227 data/0019/000228 data/0019/000229 data/0019/000230 data/0019/000231 data/0019/000232 data/0019/000233 data/0019/000234 data/0019/000235 data/0019/000236 data/0019/000237 data/0019/000238 data/0019/000239 data/0019/000240 data/0019/000241 data/0019/000242 data/0019/000243 data/0019/000244 data/0019/000245 data/0019/000246 data/0019/000247 data/0019/000248 data/0019/000249 data/0019/000250 data/0019/000251 data/0019/000252 data/0019/000253 data/0019/000254 data/0019/000255 data/0019/000256 data/0019/000257 data/0019/000258 data/0019/000259 data/0019/000260 data/0019/000261 data/0019/000262 data/0019/000263 data/0019/000264 data/0019/000265 data/0019/000266 data/0019/000267 data/0019/000268 data/0019/000269 data/0019/000270 data/0019/000271 data/0019/000272 data/0019/000273 data/0019/000274 data/0019/000275 data/0019/000276 data/0019/000277 data/0019/000278 data/0019/000279 data/0019/000280 data/0019/000281 data/0019/000282 data/0019/000283 data/0019/000284 data/0019/000285 data/0019/000286 data/0019/000287 data/0019/000288 data/0019/000289 data/0019/000290 data/0019/000291 data/0019/000292 data/0019/000293 data/0019/000294 data/0019/000295 data/0019/000296 data/0019/000297 data/0019/000298 data/0019/000299 data/0019/000300 data/0019/000301 data/0019/000302 data/0019/000303 data/0019/000304 data/0019/000305 data/0019/000306 data/0019/000307 data/0019/000308 data/0019/000309 data/0019/000310 data/0019/000311 data/0019/000312 data/0019/000313 data/0019/000314 data/0019/000315 data/0019/000316 data/0019/000317 data/0019/000318 data/0019/000319 data/0019/000320 data/0019/000321 data/0019/000322 data/0019/000323 data/0019/000324 data/0019/000325 data/0019/000326 data/0019/000327 data/0019/000328 data/0019/000329 data/0019/000330 data/0019/000331 data/0019/000332 data/0019/000333 data/0019/000334 data/0019/000335 data/0019/000336 data/0019/000337 data/0019/000338 data/0019/000339 data/0019/000340 data/0019/000341 data/0019/000342 data/0019/000343 data/0019/000344 data/0019/000345 data/0019/000346 data/0019/000347 data/0019/000348 data/0019/000349 data/0019/000350 data/0019/000351 data/0019/000352 data/0019/000353 data/0019/000354 data/0019/000355 data/0019/000356 data/0019/000357 data/0019/000358 data/0019/000359 data/0019/000360 data/0019/000361 data/0019/000362 data/0019/000363 data/0019/000364 data/0019/000365 data/0019/000366 data/0019/000367 data/0019/000368 data/0019/000369 data/0019/000370 data/0019/000371 data/0019/000372 data/0019/000373 data/0019/000374 data/0019/000375 data/0019/000376 data/0019/000377 data/0019/000378 data/0019/000379 data/0019/000380 data/0019/000381 data/0019/000382 data/0019/000383 data/0019/000384 data/0019/000385 data/0019/000386 data/0019/000387 data/0019/000388 data/0019/000389 data/0019/000390 data/0019/000391 data/0019/000392 data/0019/000393 data/0019/000394 data/0019/000395 data/0019/000396 data/0019/000397 data/0019/000398 data/0019/000399 data/0019/000400 data/0019/000401 data/0019/000402 data/0019/000403 data/0019/000404 data/0019/000405 data/0019/000406 data/0019/000407 data/0019/000408 data/0019/000409 data/0019/000410 data/0019/000411 data/0019/000412 data/0019/000413 data/0019/000414 data/0019/000415 data/0019/000416 data/0019/000417 data/0019/000418 data/0019/000419 data/0019/000420 data/0019/000421 data/0019/000422 data/0019/000423 data/0019/000424 data/0019/000425 data/0019/000426 data/0019/000427 data/0019/000428 data/0019/000429 data/0019/000430 data/0019/000431 data/0019/000432 data/0019/000433 data/0019/000434 data/0019/000435 data/0019/000436 data/0019/000437 data/0019/000438 data/0019/000439 data/0019/000440 data/0019/000441 data/0019/000442 data/0019/000443 data/0019/000444 data/0019/000445 data/0019/000446 data/0019/000447 data/0019/000448 data/0019/000449 data/0019/000450 data/0019/000451 data/0019/000452 data/0019/000453 data/0019/000454 data/0019/000455 data/0019/000456 data/0019/000457 data/0019/000458 data/0019/000459 data/0019/000460 data/0019/000461 data/0019/000462 data/0019/000463 data/0019/000464 data/0019/000465 data/0019/000466 data/0019/000467 data/0019/000468 data/0019/000469 data/0019/000470 data/0019/000471 data/0019/000472 data/0019/000473 data/0019/000474 data/0019/000475 data/0019/000476 data/0019/000477 data/0019/000478 data/0019/000479 data/0019/000480 data/0019/000481 data/0019/000482 data/0019/000483 data/0019/000484 data/0019/000485 data/0019/000486 data/0019/000487 data/0019/000488 data/0019/000489 data/0019/000490 data/0019/000491 data/0019/000492 data/0019/000493 data/0019/000494 data/0019/000495 data/0019/000496 data/0019/000497 data/0019/000498 data/0019/000499 data/0019/000500 data/0019/000501 data/0019/000502 data/0019/000503 data/0019/000504 data/0019/000505 data/0019/000506 data/0019/000507 data/0019/000508 data/0019/000509 data/0019/000510 data/0019/000511 data/0019/000512 data/0019/000513 data/0019/000514 data/0019/000515 data/0019/000516 data/0019/000517 data/0019/000518 data/0019/000519 data/0019/000520 data/0019/000521 data/0019/000522 data/0019/000523 data/0019/000524 data/0019/000525 data/0019/000526 data/0019/000527 data/0019/000528 data/0019/000529 data/0019/000530 data/0019/000531 data/0019/000532 data/0019/000533 data/0019/000534 data/0019/000535 data/0019/000536 data/0019/000537 data/0019/000538 data/0019/000539 data/0019/000540 data/0019/000541 data/0019/000542 data/0019/000543 data/0019/000544 data/0019/000545 data/0019/000546 data/0019/000547 data/0019/000548 data/0019/000549 data/0019/000550 data/0019/000551 data/0019/000552 data/0019/000553 data/0019/000554 data/0019/000555 data/0019/000556 data/0019/000557 data/0019/000558 data/0019/000559 data/0019/000560 data/0019/000561 data/0019/000562 data/0019/000563 data/0019/000564 data/0019/000565 data/0019/000566 data/0019/000567 data/0019/000568 data/0019/000569 data/0019/000570 data/0019/000571 data/0019/000572 data/0019/000573 data/0019/000574 data/0019/000575 data/0019/000576 data/0019/000577 data/0019/000578 data/0019/000579 data/0019/000580 data/0019/000581 data/0019/000582 data/0019/000583 data/0019/000584 data/0019/000585 data/0019/000586 data/0019/000587 data/0019/000588 data/0019/000589 data/0019/000590 data/0019/000591 data/0019/000592 data/0019/000593 data/0019/000594 data/0019/000595 data/0019/000596 data/0019/000597 data/0019/000598 data/0019/000599 data/0019/000600 data/0019/000601 data/0019/000602 data/0019/000603 data/0019/000604 data/0019/000605 data/0019/000606 data/0019/000607 data/0019/000608 data/0019/000609 data/0019/000610 data/0019/000611 data/0019/000612 data/0019/000613 data/0019/000614 data/0019/000615 data/0019/000616 data/0019/000617 data/0019/000618 data/0019/000619 data/0019/000620 data/0019/000621 data/0019/000622 data/0019/000623 data/0019/000624 data/0019/000625 data/0019/000626 data/0019/000627 data/0019/000628 data/0019/000629 data/0019/000630 data/0019/000631 data/0019/000632 data/0019/000633 data/0019/000634 data/0019/000635 data/0019/000636 data/0019/000637 data/0019/000638 data/0019/000639 data/0019/000640 data/0019/000641 data/0019/000642 data/0019/000643 data/0019/000644 data/0019/000645 data/0019/000646 data/0019/000647 data/0019/000648 data/0019/000649 data/0019/000650 data/0019/000651 data/0019/000652 data/0019/000653 data/0019/000654 data/0019/000655 data/0019/000656 data/0019/000657 data/0019/000658 data/0019/000659 data/0019/000660 data/0019/000661 data/0019/000662 data/0019/000663 data/0019/000664 data/0019/000665 data/0019/000666 data/0019/000667 data/0019/000668 data/0019/000669 data/0019/000670 data/0019/000671 data/0019/000672 data/0019/000673 data/0019/000674 data/0019/000675 data/0019/000676 data/0019/000677 data/0019/000678 data/0019/000679 data/0019/000680 data/0019/000681 data/0019/000682 data/0019/000683 data/0019/000684 data/0019/000685 data/0019/000686 data/0019/000687 data/0019/000688 data/0019/000689 data/0019/000690 data/0019/000691 data/0019/000692 data/0019/000693 data/0019/000694 data/0019/000695 data/0019/000696 data/0019/000697 data/0019/000698 data/0019/000699 data/0019/000700 data/0019/000701 data/0019/000702 data/0019/000703 data/0019/000704 data/0019/000705 data/0019/000706 data/0019/000707 data/0019/000708 data/0019/000709 data/0019/000710 data/0019/000711 data/0019/000712 data/0019/000713 data/0019/000714 data/0019/000715 data/0019/000716 data/0019/000717 data/0019/000718 data/0019/000719 data/0019/000720 data/0019/000721 data/0019/000722 data/0019/000723 data/0019/000724 data/0019/000725 data/0019/000726 data/0019/000727 data/0019/000728 data/0019/000729 data/0019/000730 data/0019/000731 data/0019/000732 data/0019/000733 data/0019/000734 data/0019/000735 data/0019/000736 data/0019/000737 data/0019/000738 data/0019/000739 data/0019/000740 data/0019/000741 data/0019/000742 data/0019/000743 data/0019/000744 data/0019/000745 data/0019/000746 data/0019/000747 data/0019/000748 data/0019/000749 data/0019/000750 data/0019/000751 data/0019/000752 data/0019/000753 data/0019/000754 data/0019/000755 data/0019/000756 data/0019/000757 data/0019/000758 data/0019/000759 data/0019/000760 data/0019/000761 data/0019/000762 data/0019/000763 data/0019/000764 data/0019/000765 data/0019/000766 data/0019/000767 data/0019/000768 data/0019/000769 data/0019/000770 data/0019/000771 data/0019/000772 data/0019/000773 data/0019/000774 data/0019/000775 data/0019/000776 data/0019/000777 data/0019/000778 data/0019/000779 data/0019/000780 data/0019/000781 data/0019/000782 data/0019/000783 data/0019/000784 data/0019/000785 data/0019/000786 data/0019/000787 data/0019/000788 data/0019/000789 data/0019/000790 data/0019/000791 data/0019/000792 data/0019/000793 data/0019/000794 data/0019/000795 data/0019/000796 data/0019/000797 data/0019/000798 data/0019/000799 data/0019/000800 data/0019/000801 data/0019/000802 data/0019/000803 data/0019/000804 data/0019/000805 data/0019/000806 data/0019/000807 data/0019/000808 data/0019/000809 data/0019/000810 data/0019/000811 data/0019/000812 data/0019/000813 data/0019/000814 data/0019/000815 data/0019/000816 data/0019/000817 data/0019/000818 data/0019/000819 data/0019/000820 data/0019/000821 data/0019/000822 data/0019/000823 data/0020/000001 data/0020/000002 data/0020/000003 data/0020/000004 data/0020/000005 data/0020/000006 data/0020/000007 data/0020/000008 data/0020/000009 data/0020/000010 data/0020/000011 data/0020/000012 data/0020/000013 data/0020/000014 data/0020/000015 data/0020/000016 data/0020/000017 data/0020/000018 data/0020/000019 data/0020/000020 data/0020/000021 data/0020/000022 data/0020/000023 data/0020/000024 data/0020/000025 data/0020/000026 data/0020/000027 data/0020/000028 data/0020/000029 data/0020/000030 data/0020/000031 data/0020/000032 data/0020/000033 data/0020/000034 data/0020/000035 data/0020/000036 data/0020/000037 data/0020/000038 data/0020/000039 data/0020/000040 data/0020/000041 data/0020/000042 data/0020/000043 data/0020/000044 data/0020/000045 data/0020/000046 data/0020/000047 data/0020/000048 data/0020/000049 data/0020/000050 data/0020/000051 data/0020/000052 data/0020/000053 data/0020/000054 data/0020/000055 data/0020/000056 data/0020/000057 data/0020/000058 data/0020/000059 data/0020/000060 data/0020/000061 data/0020/000062 data/0020/000063 data/0020/000064 data/0020/000065 data/0020/000066 data/0020/000067 data/0020/000068 data/0020/000069 data/0020/000070 data/0020/000071 data/0020/000072 data/0020/000073 data/0020/000074 data/0020/000075 data/0020/000076 data/0020/000077 data/0020/000078 data/0020/000079 data/0020/000080 data/0020/000081 data/0020/000082 data/0020/000083 data/0020/000084 data/0020/000085 data/0020/000086 data/0020/000087 data/0020/000088 data/0020/000089 data/0020/000090 data/0020/000091 data/0020/000092 data/0020/000093 data/0020/000094 data/0020/000095 data/0020/000096 data/0020/000097 data/0020/000098 data/0020/000099 data/0020/000100 data/0020/000101 data/0020/000102 data/0020/000103 data/0020/000104 data/0020/000105 data/0020/000106 data/0020/000107 data/0020/000108 data/0020/000109 data/0020/000110 data/0020/000111 data/0020/000112 data/0020/000113 data/0020/000114 data/0020/000115 data/0020/000116 data/0020/000117 data/0020/000118 data/0020/000119 data/0020/000120 data/0020/000121 data/0020/000122 data/0020/000123 data/0020/000124 data/0020/000125 data/0020/000126 data/0020/000127 data/0020/000128 data/0020/000129 data/0020/000130 data/0020/000131 data/0020/000132 data/0020/000133 data/0020/000134 data/0020/000135 data/0020/000136 data/0020/000137 data/0020/000138 data/0020/000139 data/0020/000140 data/0020/000141 data/0020/000142 data/0020/000143 data/0020/000144 data/0020/000145 data/0020/000146 data/0020/000147 data/0020/000148 data/0020/000149 data/0020/000150 data/0020/000151 data/0020/000152 data/0020/000153 data/0020/000154 data/0020/000155 data/0020/000156 data/0020/000157 data/0020/000158 data/0020/000159 data/0020/000160 data/0020/000161 data/0020/000162 data/0020/000163 data/0020/000164 data/0020/000165 data/0020/000166 data/0020/000167 data/0020/000168 data/0020/000169 data/0020/000170 data/0020/000171 data/0020/000172 data/0020/000173 data/0020/000174 data/0020/000175 data/0020/000176 data/0020/000177 data/0020/000178 data/0020/000179 data/0020/000180 data/0020/000181 data/0020/000182 data/0020/000183 data/0020/000184 data/0020/000185 data/0020/000186 data/0020/000187 data/0020/000188 data/0020/000189 data/0020/000190 data/0020/000191 data/0020/000192 data/0020/000193 data/0020/000194 data/0020/000195 data/0020/000196 data/0020/000197 data/0020/000198 data/0020/000199 data/0020/000200 data/0020/000201 data/0020/000202 data/0020/000203 data/0020/000204 data/0020/000205 data/0020/000206 data/0020/000207 data/0020/000208 data/0020/000209 data/0020/000210 data/0020/000211 data/0020/000212 data/0020/000213 data/0020/000214 data/0020/000215 data/0020/000216 data/0020/000217 data/0020/000218 data/0020/000219 data/0020/000220 data/0020/000221 data/0020/000222 data/0020/000223 data/0020/000224 data/0020/000225 data/0020/000226 data/0020/000227 data/0020/000228 data/0020/000229 data/0020/000230 data/0020/000231 data/0020/000232 data/0020/000233 data/0020/000234 data/0020/000235 data/0020/000236 data/0020/000237 data/0020/000238 data/0020/000239 data/0020/000240 data/0020/000241 data/0020/000242 data/0020/000243 data/0020/000244 data/0020/000245 data/0020/000246 data/0020/000247 data/0020/000248 data/0020/000249 data/0020/000250 data/0020/000251 data/0020/000252 data/0020/000253 data/0020/000254 data/0020/000255 data/0020/000256 data/0020/000257 data/0020/000258 data/0020/000259 data/0020/000260 data/0020/000261 data/0020/000262 data/0020/000263 data/0020/000264 data/0020/000265 data/0020/000266 data/0020/000267 data/0020/000268 data/0020/000269 data/0020/000270 data/0020/000271 data/0020/000272 data/0020/000273 data/0020/000274 data/0020/000275 data/0020/000276 data/0020/000277 data/0020/000278 data/0020/000279 data/0020/000280 data/0020/000281 data/0020/000282 data/0020/000283 data/0020/000284 data/0020/000285 data/0020/000286 data/0020/000287 data/0020/000288 data/0020/000289 data/0020/000290 data/0020/000291 data/0020/000292 data/0020/000293 data/0020/000294 data/0020/000295 data/0020/000296 data/0020/000297 data/0020/000298 data/0020/000299 data/0020/000300 data/0020/000301 data/0020/000302 data/0020/000303 data/0020/000304 data/0020/000305 data/0020/000306 data/0020/000307 data/0020/000308 data/0020/000309 data/0020/000310 data/0020/000311 data/0020/000312 data/0020/000313 data/0020/000314 data/0020/000315 data/0020/000316 data/0020/000317 data/0020/000318 data/0020/000319 data/0020/000320 data/0020/000321 data/0020/000322 data/0020/000323 data/0020/000324 data/0020/000325 data/0020/000326 data/0020/000327 data/0020/000328 data/0020/000329 data/0020/000330 data/0020/000331 data/0020/000332 data/0020/000333 data/0020/000334 data/0020/000335 data/0020/000336 data/0020/000337 data/0020/000338 data/0020/000339 data/0020/000340 data/0020/000341 data/0020/000342 data/0020/000343 data/0020/000344 data/0020/000345 data/0020/000346 data/0020/000347 data/0020/000348 data/0020/000349 data/0020/000350 data/0020/000351 data/0020/000352 data/0020/000353 data/0020/000354 data/0020/000355 data/0020/000356 data/0020/000357 data/0020/000358 data/0020/000359 data/0020/000360 data/0020/000361 data/0020/000362 data/0020/000363 data/0020/000364 data/0020/000365 data/0020/000366 data/0020/000367 data/0020/000368 data/0020/000369 data/0020/000370 data/0020/000371 data/0020/000372 data/0020/000373 data/0020/000374 data/0020/000375 data/0020/000376 data/0020/000377 data/0020/000378 data/0020/000379 data/0020/000380 data/0020/000381 data/0020/000382 data/0020/000383 data/0020/000384 data/0020/000385 data/0020/000386 data/0020/000387 data/0020/000388 data/0020/000389 data/0020/000390 data/0020/000391 data/0020/000392 data/0020/000393 data/0020/000394 data/0020/000395 data/0020/000396 data/0020/000397 data/0020/000398 data/0020/000399 data/0020/000400 data/0020/000401 data/0020/000402 data/0020/000403 data/0020/000404 data/0020/000405 data/0020/000406 data/0020/000407 data/0020/000408 data/0020/000409 data/0020/000410 data/0020/000411 data/0020/000412 data/0020/000413 data/0020/000414 data/0020/000415 data/0020/000416 data/0020/000417 data/0020/000418 data/0020/000419 data/0020/000420 data/0020/000421 data/0020/000422 data/0020/000423 data/0020/000424 data/0020/000425 data/0020/000426 data/0020/000427 data/0020/000428 data/0020/000429 data/0020/000430 data/0020/000431 data/0020/000432 data/0020/000433 data/0020/000434 data/0020/000435 data/0020/000436 data/0020/000437 data/0020/000438 data/0020/000439 data/0020/000440 data/0020/000441 data/0020/000442 data/0020/000443 data/0020/000444 data/0020/000445 data/0020/000446 data/0020/000447 data/0020/000448 data/0020/000449 data/0020/000450 data/0020/000451 data/0020/000452 data/0020/000453 data/0020/000454 data/0020/000455 data/0020/000456 data/0020/000457 data/0020/000458 data/0020/000459 data/0020/000460 data/0020/000461 data/0020/000462 data/0020/000463 data/0020/000464 data/0020/000465 data/0020/000466 data/0020/000467 data/0020/000468 data/0020/000469 data/0020/000470 data/0020/000471 data/0020/000472 data/0020/000473 data/0020/000474 data/0020/000475 data/0020/000476 data/0020/000477 data/0020/000478 data/0020/000479 data/0020/000480 data/0020/000481 data/0020/000482 data/0020/000483 data/0020/000484 data/0020/000485 data/0020/000486 data/0020/000487 data/0020/000488 data/0020/000489 data/0020/000490 data/0020/000491 data/0020/000492 data/0020/000493 data/0020/000494 data/0020/000495 data/0020/000496 data/0020/000497 data/0020/000498 data/0020/000499 data/0020/000500 data/0020/000501 data/0020/000502 data/0020/000503 data/0020/000504 data/0020/000505 data/0020/000506 data/0020/000507 data/0020/000508 data/0020/000509 data/0020/000510 data/0020/000511 data/0020/000512 data/0020/000513 data/0020/000514 data/0020/000515 data/0020/000516 data/0020/000517 data/0020/000518 data/0020/000519 data/0020/000520 data/0020/000521 data/0020/000522 data/0020/000523 data/0020/000524 data/0020/000525 data/0020/000526 data/0020/000527 data/0020/000528 data/0020/000529 data/0020/000530 data/0020/000531 data/0020/000532 data/0020/000533 data/0020/000534 data/0020/000535 data/0020/000536 data/0020/000537 data/0020/000538 data/0020/000539 data/0020/000540 data/0020/000541 data/0020/000542 data/0020/000543 data/0020/000544 data/0020/000545 data/0020/000546 data/0020/000547 data/0020/000548 data/0020/000549 data/0020/000550 data/0020/000551 data/0020/000552 data/0020/000553 data/0020/000554 data/0020/000555 data/0020/000556 data/0020/000557 data/0020/000558 data/0020/000559 data/0020/000560 data/0020/000561 data/0020/000562 data/0020/000563 data/0020/000564 data/0020/000565 data/0020/000566 data/0020/000567 data/0020/000568 data/0020/000569 data/0020/000570 data/0020/000571 data/0020/000572 data/0020/000573 data/0020/000574 data/0020/000575 data/0020/000576 data/0020/000577 data/0020/000578 data/0020/000579 data/0020/000580 data/0020/000581 data/0020/000582 data/0020/000583 data/0020/000584 data/0020/000585 data/0020/000586 data/0020/000587 data/0020/000588 data/0020/000589 data/0020/000590 data/0020/000591 data/0020/000592 data/0020/000593 data/0020/000594 data/0020/000595 data/0020/000596 data/0020/000597 data/0020/000598 data/0020/000599 data/0020/000600 data/0020/000601 data/0020/000602 data/0020/000603 data/0020/000604 data/0020/000605 data/0020/000606 data/0020/000607 data/0020/000608 data/0020/000609 data/0020/000610 data/0020/000611 data/0020/000612 data/0020/000613 data/0020/000614 data/0020/000615 data/0020/000616 data/0020/000617 data/0020/000618 data/0020/000619 data/0020/000620 data/0020/000621 data/0020/000622 data/0020/000623 data/0020/000624 data/0020/000625 data/0020/000626 data/0020/000627 data/0020/000628 data/0020/000629 data/0020/000630 data/0020/000631 data/0020/000632 data/0020/000633 data/0020/000634 data/0020/000635 data/0020/000636 data/0020/000637 data/0020/000638 data/0020/000639 data/0020/000640 data/0020/000641 data/0020/000642 data/0020/000643 data/0020/000644 data/0020/000645 data/0020/000646 data/0020/000647 data/0020/000648 data/0020/000649 data/0020/000650 data/0020/000651 data/0020/000652 data/0020/000653 data/0020/000654 data/0020/000655 data/0020/000656 data/0020/000657 data/0020/000658 data/0020/000659 data/0020/000660 data/0020/000661 data/0020/000662 data/0020/000663 data/0020/000664 data/0020/000665 data/0020/000666 data/0020/000667 data/0020/000668 data/0020/000669 data/0020/000670 data/0020/000671 data/0020/000672 data/0020/000673 data/0020/000674 data/0020/000675 data/0020/000676 data/0020/000677 data/0020/000678 data/0020/000679 data/0020/000680 data/0020/000681 data/0020/000682 data/0020/000683 data/0020/000684 data/0020/000685 data/0020/000686 data/0020/000687 data/0020/000688 data/0020/000689 data/0020/000690 data/0020/000691 data/0020/000692 data/0020/000693 data/0020/000694 data/0020/000695 data/0020/000696 data/0020/000697 data/0020/000698 data/0020/000699 data/0020/000700 data/0020/000701 data/0020/000702 data/0020/000703 data/0020/000704 data/0020/000705 data/0020/000706 data/0020/000707 data/0020/000708 data/0020/000709 data/0020/000710 data/0020/000711 data/0020/000712 data/0020/000713 data/0020/000714 data/0020/000715 data/0020/000716 data/0020/000717 data/0020/000718 data/0020/000719 data/0020/000720 data/0020/000721 data/0020/000722 data/0020/000723 data/0020/000724 data/0020/000725 data/0020/000726 data/0020/000727 data/0020/000728 data/0020/000729 data/0020/000730 data/0020/000731 data/0020/000732 data/0020/000733 data/0020/000734 data/0020/000735 data/0020/000736 data/0020/000737 data/0020/000738 data/0020/000739 data/0020/000740 data/0020/000741 data/0020/000742 data/0020/000743 data/0020/000744 data/0020/000745 data/0020/000746 data/0020/000747 data/0020/000748 data/0020/000749 data/0020/000750 data/0020/000751 data/0020/000752 data/0020/000753 data/0020/000754 data/0020/000755 data/0020/000756 data/0020/000757 data/0020/000758 data/0020/000759 data/0020/000760 data/0020/000761 data/0020/000762 data/0020/000763 data/0020/000764 data/0020/000765 data/0020/000766 data/0020/000767 data/0020/000768 data/0020/000769 data/0020/000770 data/0020/000771 data/0020/000772 data/0020/000773 data/0020/000774 data/0020/000775 data/0020/000776 data/0020/000777 data/0020/000778 data/0020/000779 data/0020/000780 data/0020/000781 data/0020/000782 data/0020/000783 data/0020/000784 data/0020/000785 data/0020/000786 data/0020/000787 data/0020/000788 data/0020/000789 data/0020/000790 data/0020/000791 data/0020/000792 data/0020/000793 data/0020/000794 data/0020/000795 data/0020/000796 data/0020/000797 data/0020/000798 data/0020/000799 data/0020/000800 data/0020/000801 data/0020/000802 data/0020/000803 data/0020/000804 data/0020/000805 data/0020/000806 data/0020/000807 data/0020/000808 data/0020/000809 data/0020/000810 data/0020/000811 data/0020/000812 data/0020/000813 data/0020/000814 data/0020/000815 data/0020/000816 data/0020/000817 data/0020/000818 data/0020/000819 data/0020/000820 data/0020/000821 data/0020/000822 data/0020/000823 data/0020/000824 data/0020/000825 data/0020/000826 data/0020/000827 data/0020/000828 data/0020/000829 data/0020/000830 data/0020/000831 data/0020/000832 data/0020/000833 data/0020/000834 data/0020/000835 data/0020/000836 data/0020/000837 data/0020/000838 data/0020/000839 data/0020/000840 data/0020/000841 data/0020/000842 data/0020/000843 data/0020/000844 data/0020/000845 data/0020/000846 data/0020/000847 data/0020/000848 data/0020/000849 data/0020/000850 data/0020/000851 data/0020/000852 data/0020/000853 data/0020/000854 data/0020/000855 data/0020/000856 data/0020/000857 data/0020/000858 data/0020/000859 data/0020/000860 data/0020/000861 data/0020/000862 data/0020/000863 data/0020/000864 data/0020/000865 data/0020/000866 data/0020/000867 data/0020/000868 data/0020/000869 data/0020/000870 data/0020/000871 data/0020/000872 data/0020/000873 data/0020/000874 data/0020/000875 data/0020/000876 data/0020/000877 data/0020/000878 data/0020/000879 data/0020/000880 data/0020/000881 data/0020/000882 data/0020/000883 data/0020/000884 data/0020/000885 data/0020/000886 data/0020/000887 data/0020/000888 data/0020/000889 data/0020/000890 data/0020/000891 data/0020/000892 data/0020/000893 data/0020/000894 data/0020/000895 data/0020/000896 data/0020/000897 data/0020/000898 data/0020/000899 data/0020/000900 data/0020/000901 data/0021/000001 data/0021/000002 data/0021/000003 data/0021/000004 data/0021/000005 data/0021/000006 data/0021/000007 data/0021/000008 data/0021/000009 data/0021/000010 data/0021/000011 data/0021/000012 data/0021/000013 data/0021/000014 data/0021/000015 data/0021/000016 data/0021/000017 data/0021/000018 data/0021/000019 data/0021/000020 data/0021/000021 data/0021/000022 data/0021/000023 data/0021/000024 data/0021/000025 data/0021/000026 data/0021/000027 data/0021/000028 data/0021/000029 data/0021/000030 data/0021/000031 data/0021/000032 data/0021/000033 data/0021/000034 data/0021/000035 data/0021/000036 data/0021/000037 data/0021/000038 data/0021/000039 data/0021/000040 data/0021/000041 data/0021/000042 data/0021/000043 data/0021/000044 data/0021/000045 data/0021/000046 data/0021/000047 data/0021/000048 data/0021/000049 data/0021/000050 data/0021/000051 data/0021/000052 data/0021/000053 data/0021/000054 data/0021/000055 data/0021/000056 data/0021/000057 data/0021/000058 data/0021/000059 data/0021/000060 data/0021/000061 data/0021/000062 data/0021/000063 data/0021/000064 data/0021/000065 data/0021/000066 data/0021/000067 data/0021/000068 data/0021/000069 data/0021/000070 data/0021/000071 data/0021/000072 data/0021/000073 data/0021/000074 data/0021/000075 data/0021/000076 data/0021/000077 data/0021/000078 data/0021/000079 data/0021/000080 data/0021/000081 data/0021/000082 data/0021/000083 data/0021/000084 data/0021/000085 data/0021/000086 data/0021/000087 data/0021/000088 data/0021/000089 data/0021/000090 data/0021/000091 data/0021/000092 data/0021/000093 data/0021/000094 data/0021/000095 data/0021/000096 data/0021/000097 data/0021/000098 data/0021/000099 data/0021/000100 data/0021/000101 data/0021/000102 data/0021/000103 data/0021/000104 data/0021/000105 data/0021/000106 data/0021/000107 data/0021/000108 data/0021/000109 data/0021/000110 data/0021/000111 data/0021/000112 data/0021/000113 data/0021/000114 data/0021/000115 data/0021/000116 data/0021/000117 data/0021/000118 data/0021/000119 data/0021/000120 data/0021/000121 data/0021/000122 data/0021/000123 data/0021/000124 data/0021/000125 data/0021/000126 data/0021/000127 data/0021/000128 data/0021/000129 data/0021/000130 data/0021/000131 data/0021/000132 data/0021/000133 data/0021/000134 data/0021/000135 data/0021/000136 data/0021/000137 data/0021/000138 data/0021/000139 data/0021/000140 data/0021/000141 data/0021/000142 data/0021/000143 data/0021/000144 data/0021/000145 data/0021/000146 data/0021/000147 data/0021/000148 data/0021/000149 data/0021/000150 data/0021/000151 data/0021/000152 data/0021/000153 data/0021/000154 data/0021/000155 data/0021/000156 data/0021/000157 data/0021/000158 data/0021/000159 data/0021/000160 data/0021/000161 data/0021/000162 data/0021/000163 data/0021/000164 data/0021/000165 data/0021/000166 data/0021/000167 data/0021/000168 data/0021/000169 data/0021/000170 data/0021/000171 data/0021/000172 data/0021/000173 data/0021/000174 data/0021/000175 data/0021/000176 data/0021/000177 data/0021/000178 data/0021/000179 data/0021/000180 data/0021/000181 data/0021/000182 data/0021/000183 data/0021/000184 data/0021/000185 data/0021/000186 data/0021/000187 data/0021/000188 data/0021/000189 data/0021/000190 data/0021/000191 data/0021/000192 data/0021/000193 data/0021/000194 data/0021/000195 data/0021/000196 data/0021/000197 data/0021/000198 data/0021/000199 data/0021/000200 data/0021/000201 data/0021/000202 data/0021/000203 data/0021/000204 data/0021/000205 data/0021/000206 data/0021/000207 data/0021/000208 data/0021/000209 data/0021/000210 data/0021/000211 data/0021/000212 data/0021/000213 data/0021/000214 data/0021/000215 data/0021/000216 data/0021/000217 data/0021/000218 data/0021/000219 data/0021/000220 data/0021/000221 data/0021/000222 data/0021/000223 data/0021/000224 data/0021/000225 data/0021/000226 data/0021/000227 data/0021/000228 data/0021/000229 data/0021/000230 data/0021/000231 data/0021/000232 data/0021/000233 data/0021/000234 data/0021/000235 data/0021/000236 data/0021/000237 data/0021/000238 data/0021/000239 data/0021/000240 data/0021/000241 data/0021/000242 data/0021/000243 data/0021/000244 data/0021/000245 data/0021/000246 data/0021/000247 data/0021/000248 data/0021/000249 data/0021/000250 data/0021/000251 data/0021/000252 data/0021/000253 data/0021/000254 data/0021/000255 data/0021/000256 data/0021/000257 data/0021/000258 data/0021/000259 data/0021/000260 data/0021/000261 data/0021/000262 data/0021/000263 data/0021/000264 data/0021/000265 data/0021/000266 data/0021/000267 data/0021/000268 data/0021/000269 data/0021/000270 data/0021/000271 data/0021/000272 data/0021/000273 data/0021/000274 data/0021/000275 data/0021/000276 data/0021/000277 data/0021/000278 data/0021/000279 data/0021/000280 data/0021/000281 data/0021/000282 data/0021/000283 data/0021/000284 data/0021/000285 data/0021/000286 data/0021/000287 data/0021/000288 data/0021/000289 data/0021/000290 data/0021/000291 data/0021/000292 data/0021/000293 data/0021/000294 data/0021/000295 data/0021/000296 data/0021/000297 data/0021/000298 data/0021/000299 data/0021/000300 data/0021/000301 data/0021/000302 data/0021/000303 data/0021/000304 data/0021/000305 data/0021/000306 data/0021/000307 data/0021/000308 data/0021/000309 data/0021/000310 data/0021/000311 data/0021/000312 data/0021/000313 data/0021/000314 data/0021/000315 data/0021/000316 data/0021/000317 data/0021/000318 data/0021/000319 data/0021/000320 data/0021/000321 data/0021/000322 data/0021/000323 data/0021/000324 data/0021/000325 data/0021/000326 data/0021/000327 data/0021/000328 data/0021/000329 data/0021/000330 data/0021/000331 data/0021/000332 data/0021/000333 data/0021/000334 data/0021/000335 data/0021/000336 data/0021/000337 data/0021/000338 data/0021/000339 data/0021/000340 data/0021/000341 data/0021/000342 data/0021/000343 data/0021/000344 data/0021/000345 data/0021/000346 data/0021/000347 data/0021/000348 data/0021/000349 data/0021/000350 data/0021/000351 data/0021/000352 data/0021/000353 data/0021/000354 data/0021/000355 data/0021/000356 data/0021/000357 data/0021/000358 data/0021/000359 data/0021/000360 data/0021/000361 data/0021/000362 data/0021/000363 data/0021/000364 data/0021/000365 data/0021/000366 data/0021/000367 data/0021/000368 data/0021/000369 data/0021/000370 data/0021/000371 data/0021/000372 data/0021/000373 data/0021/000374 data/0021/000375 data/0021/000376 data/0021/000377 data/0021/000378 data/0021/000379 data/0021/000380 data/0021/000381 data/0021/000382 data/0021/000383 data/0021/000384 data/0021/000385 data/0021/000386 data/0021/000387 data/0021/000388 data/0021/000389 data/0021/000390 data/0021/000391 data/0021/000392 data/0021/000393 data/0021/000394 data/0021/000395 data/0021/000396 data/0021/000397 data/0021/000398 data/0021/000399 data/0021/000400 data/0021/000401 data/0021/000402 data/0021/000403 data/0021/000404 data/0021/000405 data/0021/000406 data/0021/000407 data/0021/000408 data/0021/000409 data/0021/000410 data/0021/000411 data/0021/000412 data/0021/000413 data/0021/000414 data/0021/000415 data/0021/000416 data/0021/000417 data/0021/000418 data/0021/000419 data/0021/000420 data/0021/000421 data/0021/000422 data/0021/000423 data/0021/000424 data/0021/000425 data/0021/000426 data/0021/000427 data/0021/000428 data/0021/000429 data/0021/000430 data/0021/000431 data/0021/000432 data/0021/000433 data/0021/000434 data/0021/000435 data/0021/000436 data/0021/000437 data/0021/000438 data/0021/000439 data/0021/000440 data/0021/000441 data/0021/000442 data/0021/000443 data/0021/000444 data/0021/000445 data/0021/000446 data/0021/000447 data/0021/000448 data/0021/000449 data/0021/000450 data/0021/000451 data/0021/000452 data/0021/000453 data/0021/000454 data/0021/000455 data/0021/000456 data/0021/000457 data/0021/000458 data/0021/000459 data/0021/000460 data/0021/000461 data/0021/000462 data/0021/000463 data/0021/000464 data/0021/000465 data/0021/000466 data/0021/000467 data/0021/000468 data/0021/000469 data/0021/000470 data/0021/000471 data/0021/000472 data/0021/000473 data/0021/000474 data/0021/000475 data/0021/000476 data/0021/000477 data/0021/000478 data/0021/000479 data/0021/000480 data/0021/000481 data/0021/000482 data/0021/000483 data/0021/000484 data/0021/000485 data/0021/000486 data/0021/000487 data/0021/000488 data/0021/000489 data/0021/000490 data/0021/000491 data/0021/000492 data/0021/000493 data/0021/000494 data/0021/000495 data/0021/000496 data/0021/000497 data/0021/000498 data/0021/000499 data/0021/000500 data/0021/000501 data/0021/000502 data/0021/000503 data/0021/000504 data/0021/000505 data/0021/000506 data/0021/000507 data/0021/000508 data/0021/000509 data/0021/000510 data/0021/000511 data/0021/000512 data/0021/000513 data/0021/000514 data/0021/000515 data/0021/000516 data/0021/000517 data/0021/000518 data/0021/000519 data/0021/000520 data/0021/000521 data/0021/000522 data/0021/000523 data/0021/000524 data/0021/000525 data/0021/000526 data/0021/000527 data/0021/000528 data/0021/000529 data/0021/000530 data/0021/000531 data/0021/000532 data/0021/000533 data/0021/000534 data/0021/000535 data/0021/000536 data/0021/000537 data/0021/000538 data/0021/000539 data/0021/000540 data/0021/000541 data/0021/000542 data/0021/000543 data/0021/000544 data/0021/000545 data/0021/000546 data/0021/000547 data/0021/000548 data/0021/000549 data/0021/000550 data/0021/000551 data/0021/000552 data/0021/000553 data/0021/000554 data/0021/000555 data/0021/000556 data/0021/000557 data/0021/000558 data/0021/000559 data/0021/000560 data/0021/000561 data/0021/000562 data/0021/000563 data/0021/000564 data/0021/000565 data/0021/000566 data/0021/000567 data/0021/000568 data/0021/000569 data/0021/000570 data/0021/000571 data/0021/000572 data/0021/000573 data/0021/000574 data/0021/000575 data/0021/000576 data/0021/000577 data/0021/000578 data/0021/000579 data/0021/000580 data/0021/000581 data/0021/000582 data/0021/000583 data/0021/000584 data/0021/000585 data/0021/000586 data/0021/000587 data/0021/000588 data/0021/000589 data/0021/000590 data/0021/000591 data/0021/000592 data/0021/000593 data/0021/000594 data/0021/000595 data/0021/000596 data/0021/000597 data/0021/000598 data/0021/000599 data/0021/000600 data/0021/000601 data/0021/000602 data/0021/000603 data/0021/000604 data/0021/000605 data/0021/000606 data/0021/000607 data/0021/000608 data/0021/000609 data/0021/000610 data/0021/000611 data/0021/000612 data/0021/000613 data/0021/000614 data/0021/000615 data/0021/000616 data/0021/000617 data/0021/000618 data/0021/000619 data/0021/000620 data/0021/000621 data/0021/000622 data/0021/000623 data/0021/000624 data/0021/000625 data/0021/000626 data/0021/000627 data/0021/000628 data/0021/000629 data/0021/000630 data/0021/000631 data/0021/000632 data/0021/000633 data/0021/000634 data/0021/000635 data/0021/000636 data/0021/000637 data/0021/000638 data/0021/000639 data/0021/000640 data/0021/000641 data/0021/000642 data/0021/000643 data/0021/000644 data/0021/000645 data/0021/000646 data/0021/000647 data/0021/000648 data/0021/000649 data/0021/000650 data/0021/000651 data/0021/000652 data/0021/000653 data/0021/000654 data/0021/000655 data/0021/000656 data/0021/000657 data/0021/000658 data/0021/000659 data/0021/000660 data/0021/000661 data/0021/000662 data/0021/000663 data/0021/000664 data/0021/000665 data/0021/000666 data/0021/000667 data/0021/000668 data/0021/000669 data/0021/000670 data/0021/000671 data/0021/000672 data/0021/000673 data/0021/000674 data/0021/000675 data/0021/000676 data/0021/000677 data/0021/000678 data/0021/000679 data/0021/000680 data/0021/000681 data/0021/000682 data/0021/000683 data/0021/000684 data/0021/000685 data/0021/000686 data/0021/000687 data/0021/000688 data/0021/000689 data/0021/000690 data/0021/000691 data/0021/000692 data/0021/000693 data/0021/000694 data/0021/000695 data/0021/000696 data/0021/000697 data/0021/000698 data/0021/000699 data/0021/000700 data/0021/000701 data/0021/000702 data/0021/000703 data/0021/000704 data/0021/000705 data/0021/000706 data/0021/000707 data/0021/000708 data/0021/000709 data/0021/000710 data/0021/000711 data/0021/000712 data/0021/000713 data/0021/000714 data/0021/000715 data/0021/000716 data/0021/000717 data/0021/000718 data/0021/000719 data/0021/000720 data/0021/000721 data/0021/000722 data/0021/000723 data/0021/000724 data/0021/000725 data/0021/000726 data/0021/000727 data/0021/000728 data/0021/000729 data/0021/000730 data/0021/000731 data/0021/000732 data/0021/000733 data/0021/000734 data/0021/000735 data/0021/000736 data/0021/000737 data/0021/000738 data/0021/000739 data/0021/000740 data/0021/000741 data/0021/000742 data/0021/000743 data/0021/000744 data/0021/000745 data/0021/000746 data/0021/000747 data/0021/000748 data/0021/000749 data/0021/000750 data/0021/000751 data/0021/000752 data/0021/000753 data/0021/000754 data/0021/000755 data/0021/000756 data/0021/000757 data/0021/000758 data/0021/000759 data/0021/000760 data/0021/000761 data/0021/000762 data/0021/000763 data/0021/000764 data/0021/000765 data/0021/000766 data/0021/000767 data/0021/000768 data/0021/000769 data/0021/000770 data/0021/000771 data/0021/000772 data/0021/000773 data/0021/000774 data/0021/000775 data/0021/000776 data/0021/000777 data/0021/000778 data/0021/000779 data/0021/000780 data/0021/000781 data/0021/000782 data/0021/000783 data/0021/000784 data/0021/000785 data/0021/000786 data/0021/000787 data/0021/000788 data/0021/000789 data/0021/000790 data/0021/000791 data/0021/000792 data/0021/000793 data/0021/000794 data/0021/000795 data/0021/000796 data/0021/000797 data/0021/000798 data/0021/000799 data/0021/000800 data/0021/000801 data/0021/000802 data/0021/000803 data/0021/000804 data/0021/000805 data/0021/000806 data/0021/000807 data/0021/000808 data/0021/000809 data/0021/000810 data/0021/000811 data/0021/000812 data/0021/000813 data/0021/000814 data/0021/000815 data/0021/000816 data/0021/000817 data/0021/000818 data/0021/000819 data/0021/000820 data/0021/000821 data/0021/000822 data/0021/000823 data/0021/000824 data/0021/000825 data/0021/000826 data/0021/000827 data/0021/000828 data/0021/000829 data/0021/000830 data/0021/000831 data/0021/000832 data/0021/000833 data/0021/000834 data/0021/000835 data/0021/000836 data/0021/000837 data/0021/000838 data/0021/000839 data/0021/000840 data/0021/000841 data/0021/000842 data/0021/000843 data/0021/000844 data/0021/000845 data/0021/000846 data/0021/000847 data/0021/000848 data/0021/000849 data/0021/000850 data/0021/000851 data/0021/000852 data/0021/000853 data/0021/000854 data/0021/000855 data/0021/000856 data/0021/000857 data/0021/000858 data/0021/000859 data/0021/000860 data/0021/000861 data/0021/000862 data/0021/000863 data/0021/000864 data/0021/000865 data/0021/000866 data/0021/000867 data/0021/000868 data/0021/000869 data/0021/000870 data/0021/000871 data/0021/000872 data/0021/000873 data/0021/000874 data/0021/000875 data/0021/000876 data/0021/000877 data/0021/000878 data/0021/000879 data/0021/000880 data/0021/000881 data/0021/000882 data/0021/000883 data/0021/000884 data/0021/000885 data/0021/000886 data/0021/000887 data/0021/000888 data/0021/000889 data/0021/000890 data/0021/000891 data/0021/000892 data/0021/000893 data/0021/000894 data/0021/000895 data/0021/000896 data/0021/000897 data/0021/000898 data/0021/000899 data/0021/000900 data/0021/000901 data/0021/000902 data/0021/000903 data/0021/000904 data/0021/000905 data/0021/000906 data/0021/000907 data/0021/000908 data/0021/000909 data/0021/000910 data/0021/000911 data/0021/000912 data/0021/000913 data/0021/000914 data/0021/000915 data/0021/000916 data/0021/000917 data/0021/000918 data/0021/000919 data/0021/000920 data/0021/000921 data/0021/000922 data/0021/000923 data/0021/000924 data/0021/000925 data/0021/000926 data/0021/000927 data/0021/000928 data/0021/000929 data/0021/000930 data/0021/000931 data/0021/000932 data/0021/000933 data/0021/000934 data/0021/000935 data/0021/000936 data/0021/000937 data/0021/000938 data/0021/000939 data/0021/000940 data/0021/000941 data/0021/000942 data/0021/000943 data/0021/000944 data/0021/000945 data/0021/000946 data/0021/000947 data/0021/000948 data/0021/000949 data/0021/000950 data/0021/000951 data/0021/000952 data/0021/000953 data/0021/000954 data/0021/000955 data/0021/000956 data/0021/000957 data/0021/000958 data/0021/000959 data/0021/000960 data/0021/000961 data/0021/000962 data/0021/000963 data/0021/000964 data/0021/000965 data/0021/000966 data/0021/000967 data/0021/000968 data/0021/000969 data/0021/000970 data/0021/000971 data/0021/000972 data/0021/000973 data/0021/000974 data/0021/000975 data/0021/000976 data/0021/000977 data/0021/000978 data/0021/000979 data/0021/000980 data/0021/000981 data/0021/000982 data/0021/000983 data/0021/000984 data/0021/000985 data/0021/000986 data/0021/000987 data/0021/000988 data/0021/000989 data/0021/000990 data/0021/000991 data/0021/000992 data/0021/000993 data/0021/000994 data/0021/000995 data/0021/000996 data/0021/000997 data/0021/000998 data/0021/000999 data/0021/001000 data/0021/001001 data/0021/001002 data/0021/001003 data/0021/001004 data/0021/001005 data/0021/001006 data/0021/001007 data/0021/001008 data/0021/001009 data/0021/001010 data/0021/001011 data/0021/001012 data/0021/001013 data/0021/001014 data/0021/001015 data/0021/001016 data/0021/001017 data/0021/001018 data/0021/001019 data/0021/001020 data/0021/001021 data/0021/001022 data/0022/000001 data/0022/000002 data/0022/000003 data/0022/000004 data/0022/000005 data/0022/000006 data/0022/000007 data/0022/000008 data/0022/000009 data/0022/000010 data/0022/000011 data/0022/000012 data/0022/000013 data/0022/000014 data/0022/000015 data/0022/000016 data/0022/000017 data/0022/000018 data/0022/000019 data/0022/000020 data/0022/000021 data/0022/000022 data/0022/000023 data/0022/000024 data/0022/000025 data/0022/000026 data/0022/000027 data/0022/000028 data/0022/000029 data/0022/000030 data/0022/000031 data/0022/000032 data/0022/000033 data/0022/000034 data/0022/000035 data/0022/000036 data/0022/000037 data/0022/000038 data/0022/000039 data/0022/000040 data/0022/000041 data/0022/000042 data/0022/000043 data/0022/000044 data/0022/000045 data/0022/000046 data/0022/000047 data/0022/000048 data/0022/000049 data/0022/000050 data/0022/000051 data/0022/000052 data/0022/000053 data/0022/000054 data/0022/000055 data/0022/000056 data/0022/000057 data/0022/000058 data/0022/000059 data/0022/000060 data/0022/000061 data/0022/000062 data/0022/000063 data/0022/000064 data/0022/000065 data/0022/000066 data/0022/000067 data/0022/000068 data/0022/000069 data/0022/000070 data/0022/000071 data/0022/000072 data/0022/000073 data/0022/000074 data/0022/000075 data/0022/000076 data/0022/000077 data/0022/000078 data/0022/000079 data/0022/000080 data/0022/000081 data/0022/000082 data/0022/000083 data/0022/000084 data/0022/000085 data/0022/000086 data/0022/000087 data/0022/000088 data/0022/000089 data/0022/000090 data/0022/000091 data/0022/000092 data/0022/000093 data/0022/000094 data/0022/000095 data/0022/000096 data/0022/000097 data/0022/000098 data/0022/000099 data/0022/000100 data/0022/000101 data/0022/000102 data/0022/000103 data/0022/000104 data/0022/000105 data/0022/000106 data/0022/000107 data/0022/000108 data/0022/000109 data/0022/000110 data/0022/000111 data/0022/000112 data/0022/000113 data/0022/000114 data/0022/000115 data/0022/000116 data/0022/000117 data/0022/000118 data/0022/000119 data/0022/000120 data/0022/000121 data/0022/000122 data/0022/000123 data/0022/000124 data/0022/000125 data/0022/000126 data/0022/000127 data/0022/000128 data/0022/000129 data/0022/000130 data/0022/000131 data/0022/000132 data/0022/000133 data/0022/000134 data/0022/000135 data/0022/000136 data/0022/000137 data/0022/000138 data/0022/000139 data/0022/000140 data/0022/000141 data/0022/000142 data/0022/000143 data/0022/000144 data/0022/000145 data/0022/000146 data/0022/000147 data/0022/000148 data/0022/000149 data/0022/000150 data/0022/000151 data/0022/000152 data/0022/000153 data/0022/000154 data/0022/000155 data/0022/000156 data/0022/000157 data/0022/000158 data/0022/000159 data/0022/000160 data/0022/000161 data/0022/000162 data/0022/000163 data/0022/000164 data/0022/000165 data/0022/000166 data/0022/000167 data/0022/000168 data/0022/000169 data/0022/000170 data/0022/000171 data/0022/000172 data/0022/000173 data/0022/000174 data/0022/000175 data/0022/000176 data/0022/000177 data/0022/000178 data/0022/000179 data/0022/000180 data/0022/000181 data/0022/000182 data/0022/000183 data/0022/000184 data/0022/000185 data/0022/000186 data/0022/000187 data/0022/000188 data/0022/000189 data/0022/000190 data/0022/000191 data/0022/000192 data/0022/000193 data/0022/000194 data/0022/000195 data/0022/000196 data/0022/000197 data/0022/000198 data/0022/000199 data/0022/000200 data/0022/000201 data/0022/000202 data/0022/000203 data/0022/000204 data/0022/000205 data/0022/000206 data/0022/000207 data/0022/000208 data/0022/000209 data/0022/000210 data/0022/000211 data/0022/000212 data/0022/000213 data/0022/000214 data/0022/000215 data/0022/000216 data/0022/000217 data/0022/000218 data/0022/000219 data/0022/000220 data/0022/000221 data/0022/000222 data/0022/000223 data/0022/000224 data/0022/000225 data/0022/000226 data/0022/000227 data/0022/000228 data/0022/000229 data/0022/000230 data/0022/000231 data/0022/000232 data/0022/000233 data/0022/000234 data/0022/000235 data/0022/000236 data/0022/000237 data/0022/000238 data/0022/000239 data/0022/000240 data/0022/000241 data/0022/000242 data/0022/000243 data/0022/000244 data/0022/000245 data/0022/000246 data/0022/000247 data/0022/000248 data/0022/000249 data/0022/000250 data/0022/000251 data/0022/000252 data/0022/000253 data/0022/000254 data/0022/000255 data/0022/000256 data/0022/000257 data/0022/000258 data/0022/000259 data/0022/000260 data/0022/000261 data/0022/000262 data/0022/000263 data/0022/000264 data/0022/000265 data/0022/000266 data/0022/000267 data/0022/000268 data/0022/000269 data/0022/000270 data/0022/000271 data/0022/000272 data/0022/000273 data/0022/000274 data/0022/000275 data/0022/000276 data/0022/000277 data/0022/000278 data/0022/000279 data/0022/000280 data/0022/000281 data/0022/000282 data/0022/000283 data/0022/000284 data/0022/000285 data/0022/000286 data/0022/000287 data/0022/000288 data/0022/000289 data/0022/000290 data/0022/000291 data/0022/000292 data/0022/000293 data/0022/000294 data/0022/000295 data/0022/000296 data/0022/000297 data/0022/000298 data/0022/000299 data/0022/000300 data/0022/000301 data/0022/000302 data/0022/000303 data/0022/000304 data/0022/000305 data/0022/000306 data/0022/000307 data/0022/000308 data/0022/000309 data/0022/000310 data/0022/000311 data/0022/000312 data/0022/000313 data/0022/000314 data/0022/000315 data/0022/000316 data/0022/000317 data/0022/000318 data/0022/000319 data/0022/000320 data/0022/000321 data/0022/000322 data/0022/000323 data/0022/000324 data/0022/000325 data/0022/000326 data/0022/000327 data/0022/000328 data/0022/000329 data/0022/000330 data/0022/000331 data/0022/000332 data/0022/000333 data/0022/000334 data/0022/000335 data/0022/000336 data/0022/000337 data/0022/000338 data/0022/000339 data/0022/000340 data/0022/000341 data/0022/000342 data/0022/000343 data/0022/000344 data/0022/000345 data/0022/000346 data/0022/000347 data/0022/000348 data/0022/000349 data/0022/000350 data/0022/000351 data/0022/000352 data/0022/000353 data/0022/000354 data/0022/000355 data/0022/000356 data/0022/000357 data/0022/000358 data/0022/000359 data/0022/000360 data/0022/000361 data/0022/000362 data/0022/000363 data/0022/000364 data/0022/000365 data/0022/000366 data/0022/000367 data/0022/000368 data/0022/000369 data/0022/000370 data/0022/000371 data/0022/000372 data/0022/000373 data/0022/000374 data/0022/000375 data/0022/000376 data/0022/000377 data/0022/000378 data/0022/000379 data/0022/000380 data/0022/000381 data/0022/000382 data/0022/000383 data/0022/000384 data/0022/000385 data/0022/000386 data/0022/000387 data/0022/000388 data/0022/000389 data/0022/000390 data/0022/000391 data/0022/000392 data/0022/000393 data/0022/000394 data/0022/000395 data/0022/000396 data/0022/000397 data/0022/000398 data/0022/000399 data/0022/000400 data/0022/000401 data/0022/000402 data/0022/000403 data/0022/000404 data/0022/000405 data/0022/000406 data/0022/000407 data/0022/000408 data/0022/000409 data/0022/000410 data/0022/000411 data/0022/000412 data/0022/000413 data/0022/000414 data/0022/000415 data/0022/000416 data/0022/000417 data/0022/000418 data/0022/000419 data/0022/000420 data/0022/000421 data/0022/000422 data/0022/000423 data/0022/000424 data/0022/000425 data/0022/000426 data/0022/000427 data/0022/000428 data/0022/000429 data/0022/000430 data/0022/000431 data/0022/000432 data/0022/000433 data/0022/000434 data/0022/000435 data/0022/000436 data/0022/000437 data/0022/000438 data/0022/000439 data/0022/000440 data/0022/000441 data/0022/000442 data/0022/000443 data/0022/000444 data/0022/000445 data/0022/000446 data/0022/000447 data/0022/000448 data/0022/000449 data/0022/000450 data/0022/000451 data/0022/000452 data/0022/000453 data/0022/000454 data/0022/000455 data/0022/000456 data/0022/000457 data/0022/000458 data/0022/000459 data/0022/000460 data/0022/000461 data/0022/000462 data/0022/000463 data/0022/000464 data/0022/000465 data/0022/000466 data/0022/000467 data/0022/000468 data/0022/000469 data/0022/000470 data/0022/000471 data/0022/000472 data/0022/000473 data/0022/000474 data/0022/000475 data/0022/000476 data/0022/000477 data/0022/000478 data/0022/000479 data/0022/000480 data/0022/000481 data/0022/000482 data/0022/000483 data/0022/000484 data/0022/000485 data/0022/000486 data/0022/000487 data/0022/000488 data/0022/000489 data/0022/000490 data/0022/000491 data/0022/000492 data/0022/000493 data/0022/000494 data/0022/000495 data/0022/000496 data/0022/000497 data/0022/000498 data/0022/000499 data/0022/000500 data/0022/000501 data/0022/000502 data/0022/000503 data/0022/000504 data/0022/000505 data/0022/000506 data/0022/000507 data/0022/000508 data/0022/000509 data/0022/000510 data/0022/000511 data/0022/000512 data/0022/000513 data/0022/000514 data/0022/000515 data/0022/000516 data/0022/000517 data/0022/000518 data/0022/000519 data/0022/000520 data/0022/000521 data/0022/000522 data/0022/000523 data/0022/000524 data/0022/000525 data/0022/000526 data/0022/000527 data/0022/000528 data/0022/000529 data/0022/000530 data/0022/000531 data/0022/000532 data/0022/000533 data/0022/000534 data/0022/000535 data/0022/000536 data/0022/000537 data/0022/000538 data/0022/000539 data/0022/000540 data/0022/000541 data/0022/000542 data/0022/000543 data/0022/000544 data/0022/000545 data/0022/000546 data/0022/000547 data/0022/000548 data/0022/000549 data/0022/000550 data/0022/000551 data/0022/000552 data/0022/000553 data/0022/000554 data/0022/000555 data/0022/000556 data/0022/000557 data/0022/000558 data/0022/000559 data/0022/000560 data/0022/000561 data/0022/000562 data/0022/000563 data/0022/000564 data/0022/000565 data/0022/000566 data/0022/000567 data/0022/000568 data/0022/000569 data/0022/000570 data/0022/000571 data/0022/000572 data/0022/000573 data/0022/000574 data/0022/000575 data/0022/000576 data/0022/000577 data/0022/000578 data/0022/000579 data/0022/000580 data/0022/000581 data/0022/000582 data/0022/000583 data/0022/000584 data/0022/000585 data/0022/000586 data/0022/000587 data/0022/000588 data/0022/000589 data/0022/000590 data/0022/000591 data/0022/000592 data/0022/000593 data/0022/000594 data/0022/000595 data/0022/000596 data/0022/000597 data/0022/000598 data/0022/000599 data/0022/000600 data/0022/000601 data/0022/000602 data/0022/000603 data/0022/000604 data/0022/000605 data/0022/000606 data/0022/000607 data/0022/000608 data/0022/000609 data/0022/000610 data/0022/000611 data/0022/000612 data/0022/000613 data/0022/000614 data/0022/000615 data/0022/000616 data/0022/000617 data/0022/000618 data/0022/000619 data/0022/000620 data/0022/000621 data/0022/000622 data/0022/000623 data/0022/000624 data/0022/000625 data/0022/000626 data/0022/000627 data/0022/000628 data/0022/000629 data/0022/000630 data/0022/000631 data/0022/000632 data/0022/000633 data/0022/000634 data/0022/000635 data/0022/000636 data/0022/000637 data/0022/000638 data/0022/000639 data/0022/000640 data/0022/000641 data/0022/000642 data/0022/000643 data/0022/000644 data/0022/000645 data/0022/000646 data/0022/000647 data/0022/000648 data/0022/000649 data/0022/000650 data/0022/000651 data/0022/000652 data/0022/000653 data/0022/000654 data/0022/000655 data/0022/000656 data/0022/000657 data/0022/000658 data/0022/000659 data/0022/000660 data/0022/000661 data/0022/000662 data/0022/000663 data/0022/000664 data/0022/000665 data/0022/000666 data/0022/000667 data/0022/000668 data/0022/000669 data/0022/000670 data/0022/000671 data/0022/000672 data/0022/000673 data/0022/000674 data/0022/000675 data/0022/000676 data/0022/000677 data/0022/000678 data/0022/000679 data/0022/000680 data/0022/000681 data/0022/000682 data/0022/000683 data/0022/000684 data/0022/000685 data/0022/000686 data/0022/000687 data/0022/000688 data/0022/000689 data/0022/000690 data/0022/000691 data/0022/000692 data/0022/000693 data/0022/000694 data/0022/000695 data/0022/000696 data/0022/000697 data/0022/000698 data/0022/000699 data/0022/000700 data/0022/000701 data/0022/000702 data/0022/000703 data/0022/000704 data/0022/000705 data/0022/000706 data/0022/000707 data/0022/000708 data/0022/000709 data/0022/000710 data/0022/000711 data/0022/000712 data/0022/000713 data/0022/000714 data/0022/000715 data/0022/000716 data/0022/000717 data/0022/000718 data/0022/000719 data/0022/000720 data/0022/000721 data/0022/000722 data/0022/000723 data/0022/000724 data/0022/000725 data/0022/000726 data/0022/000727 data/0022/000728 data/0022/000729 data/0022/000730 data/0022/000731 data/0022/000732 data/0022/000733 data/0022/000734 data/0022/000735 data/0022/000736 data/0022/000737 data/0022/000738 data/0022/000739 data/0022/000740 data/0022/000741 data/0022/000742 data/0022/000743 data/0022/000744 data/0022/000745 data/0022/000746 data/0022/000747 data/0022/000748 data/0022/000749 data/0022/000750 data/0022/000751 data/0022/000752 data/0022/000753 data/0022/000754 data/0022/000755 data/0022/000756 data/0022/000757 data/0022/000758 data/0022/000759 data/0022/000760 data/0022/000761 data/0022/000762 data/0022/000763 data/0022/000764 data/0022/000765 data/0022/000766 data/0022/000767 data/0022/000768 data/0022/000769 data/0022/000770 data/0022/000771 data/0022/000772 data/0022/000773 data/0022/000774 data/0022/000775 data/0022/000776 data/0022/000777 data/0022/000778 data/0022/000779 data/0022/000780 data/0022/000781 data/0022/000782 data/0022/000783 data/0022/000784 data/0022/000785 data/0022/000786 data/0022/000787 data/0022/000788 data/0022/000789 data/0022/000790 data/0022/000791 data/0022/000792 data/0022/000793 data/0022/000794 data/0022/000795 data/0022/000796 data/0022/000797 data/0022/000798 data/0022/000799 data/0022/000800 data/0022/000801 data/0022/000802 data/0022/000803 data/0022/000804 data/0022/000805 data/0022/000806 data/0022/000807 data/0022/000808 data/0022/000809 data/0022/000810 data/0022/000811 data/0022/000812 data/0022/000813 data/0022/000814 data/0022/000815 data/0022/000816 data/0022/000817 data/0022/000818 data/0022/000819 data/0022/000820 data/0022/000821 data/0022/000822 data/0022/000823 data/0022/000824 data/0022/000825 data/0022/000826 data/0022/000827 data/0022/000828 data/0022/000829 data/0022/000830 data/0022/000831 data/0022/000832 data/0022/000833 data/0022/000834 data/0022/000835 data/0022/000836 data/0022/000837 data/0022/000838 data/0022/000839 data/0022/000840 data/0022/000841 data/0022/000842 data/0022/000843 data/0022/000844 data/0022/000845 data/0022/000846 data/0022/000847 data/0022/000848 data/0022/000849 data/0022/000850 data/0022/000851 data/0022/000852 data/0022/000853 data/0022/000854 data/0022/000855 data/0022/000856 data/0022/000857 data/0022/000858 data/0022/000859 data/0022/000860 data/0022/000861 data/0022/000862 data/0022/000863 data/0022/000864 data/0022/000865 data/0022/000866 data/0022/000867 data/0022/000868 data/0022/000869 data/0022/000870 data/0022/000871 data/0022/000872 data/0022/000873 data/0022/000874 data/0022/000875 data/0022/000876 data/0022/000877 data/0022/000878 data/0022/000879 data/0022/000880 data/0022/000881 data/0022/000882 data/0022/000883 data/0022/000884 data/0022/000885 data/0022/000886 data/0022/000887 data/0022/000888 data/0022/000889 data/0022/000890 data/0022/000891 data/0022/000892 data/0022/000893 data/0022/000894 data/0022/000895 data/0022/000896 data/0022/000897 data/0022/000898 data/0022/000899 data/0022/000900 data/0022/000901 data/0022/000902 data/0022/000903 data/0022/000904 data/0022/000905 data/0022/000906 data/0022/000907 data/0022/000908 data/0022/000909 data/0022/000910 data/0022/000911 data/0022/000912 data/0022/000913 data/0022/000914 data/0022/000915 data/0022/000916 data/0022/000917 data/0022/000918 data/0022/000919 data/0022/000920 data/0022/000921 data/0022/000922 data/0022/000923 data/0022/000924 data/0022/000925 data/0022/000926 data/0022/000927 data/0022/000928 data/0022/000929 data/0022/000930 data/0022/000931 data/0022/000932 data/0022/000933 data/0022/000934 data/0022/000935 data/0022/000936 data/0022/000937 data/0022/000938 data/0022/000939 data/0022/000940 data/0022/000941 data/0022/000942 data/0022/000943 data/0022/000944 data/0022/000945 data/0022/000946 data/0022/000947 data/0022/000948 data/0023/000001 data/0023/000002 data/0023/000003 data/0023/000004 data/0023/000005 data/0023/000006 data/0023/000007 data/0023/000008 data/0023/000009 data/0023/000010 data/0023/000011 data/0023/000012 data/0023/000013 data/0023/000014 data/0023/000015 data/0023/000016 data/0023/000017 data/0023/000018 data/0023/000019 data/0023/000020 data/0023/000021 data/0023/000022 data/0023/000023 data/0023/000024 data/0023/000025 data/0023/000026 data/0023/000027 data/0023/000028 data/0023/000029 data/0023/000030 data/0023/000031 data/0023/000032 data/0023/000033 data/0023/000034 data/0023/000035 data/0023/000036 data/0023/000037 data/0023/000038 data/0023/000039 data/0023/000040 data/0023/000041 data/0023/000042 data/0023/000043 data/0023/000044 data/0023/000045 data/0023/000046 data/0023/000047 data/0023/000048 data/0023/000049 data/0023/000050 data/0023/000051 data/0023/000052 data/0023/000053 data/0023/000054 data/0023/000055 data/0023/000056 data/0023/000057 data/0023/000058 data/0023/000059 data/0023/000060 data/0023/000061 data/0023/000062 data/0023/000063 data/0023/000064 data/0023/000065 data/0023/000066 data/0023/000067 data/0023/000068 data/0023/000069 data/0023/000070 data/0023/000071 data/0023/000072 data/0023/000073 data/0023/000074 data/0023/000075 data/0023/000076 data/0023/000077 data/0023/000078 data/0023/000079 data/0023/000080 data/0023/000081 data/0023/000082 data/0023/000083 data/0023/000084 data/0023/000085 data/0023/000086 data/0023/000087 data/0023/000088 data/0023/000089 data/0023/000090 data/0023/000091 data/0023/000092 data/0023/000093 data/0023/000094 data/0023/000095 data/0023/000096 data/0023/000097 data/0023/000098 data/0023/000099 data/0023/000100 data/0023/000101 data/0023/000102 data/0023/000103 data/0023/000104 data/0023/000105 data/0023/000106 data/0023/000107 data/0023/000108 data/0023/000109 data/0023/000110 data/0023/000111 data/0023/000112 data/0023/000113 data/0023/000114 data/0023/000115 data/0023/000116 data/0023/000117 data/0023/000118 data/0023/000119 data/0023/000120 data/0023/000121 data/0023/000122 data/0023/000123 data/0023/000124 data/0023/000125 data/0023/000126 data/0023/000127 data/0023/000128 data/0023/000129 data/0023/000130 data/0023/000131 data/0023/000132 data/0023/000133 data/0023/000134 data/0023/000135 data/0023/000136 data/0023/000137 data/0023/000138 data/0023/000139 data/0023/000140 data/0023/000141 data/0023/000142 data/0023/000143 data/0023/000144 data/0023/000145 data/0023/000146 data/0023/000147 data/0023/000148 data/0023/000149 data/0023/000150 data/0023/000151 data/0023/000152 data/0023/000153 data/0023/000154 data/0023/000155 data/0023/000156 data/0023/000157 data/0023/000158 data/0023/000159 data/0023/000160 data/0023/000161 data/0023/000162 data/0023/000163 data/0023/000164 data/0023/000165 data/0023/000166 data/0023/000167 data/0023/000168 data/0023/000169 data/0023/000170 data/0023/000171 data/0023/000172 data/0023/000173 data/0023/000174 data/0023/000175 data/0023/000176 data/0023/000177 data/0023/000178 data/0023/000179 data/0023/000180 data/0023/000181 data/0023/000182 data/0023/000183 data/0023/000184 data/0023/000185 data/0023/000186 data/0023/000187 data/0023/000188 data/0023/000189 data/0023/000190 data/0023/000191 data/0023/000192 data/0023/000193 data/0023/000194 data/0023/000195 data/0023/000196 data/0023/000197 data/0023/000198 data/0023/000199 data/0023/000200 data/0023/000201 data/0023/000202 data/0023/000203 data/0023/000204 data/0023/000205 data/0023/000206 data/0023/000207 data/0023/000208 data/0023/000209 data/0023/000210 data/0023/000211 data/0023/000212 data/0023/000213 data/0023/000214 data/0023/000215 data/0023/000216 data/0023/000217 data/0023/000218 data/0023/000219 data/0023/000220 data/0023/000221 data/0023/000222 data/0023/000223 data/0023/000224 data/0023/000225 data/0023/000226 data/0023/000227 data/0023/000228 data/0023/000229 data/0023/000230 data/0023/000231 data/0023/000232 data/0023/000233 data/0023/000234 data/0023/000235 data/0023/000236 data/0023/000237 data/0023/000238 data/0023/000239 data/0023/000240 data/0023/000241 data/0023/000242 data/0023/000243 data/0023/000244 data/0023/000245 data/0023/000246 data/0023/000247 data/0023/000248 data/0023/000249 data/0023/000250 data/0023/000251 data/0023/000252 data/0023/000253 data/0023/000254 data/0023/000255 data/0023/000256 data/0023/000257 data/0023/000258 data/0023/000259 data/0023/000260 data/0023/000261 data/0023/000262 data/0023/000263 data/0023/000264 data/0023/000265 data/0023/000266 data/0023/000267 data/0023/000268 data/0023/000269 data/0023/000270 data/0023/000271 data/0023/000272 data/0023/000273 data/0023/000274 data/0023/000275 data/0023/000276 data/0023/000277 data/0023/000278 data/0023/000279 data/0023/000280 data/0023/000281 data/0023/000282 data/0023/000283 data/0023/000284 data/0023/000285 data/0023/000286 data/0023/000287 data/0023/000288 data/0023/000289 data/0023/000290 data/0023/000291 data/0023/000292 data/0023/000293 data/0023/000294 data/0023/000295 data/0023/000296 data/0023/000297 data/0023/000298 data/0023/000299 data/0023/000300 data/0023/000301 data/0023/000302 data/0023/000303 data/0023/000304 data/0023/000305 data/0023/000306 data/0023/000307 data/0023/000308 data/0023/000309 data/0023/000310 data/0023/000311 data/0023/000312 data/0023/000313 data/0023/000314 data/0023/000315 data/0023/000316 data/0023/000317 data/0023/000318 data/0023/000319 data/0023/000320 data/0023/000321 data/0023/000322 data/0023/000323 data/0023/000324 data/0023/000325 data/0023/000326 data/0023/000327 data/0023/000328 data/0023/000329 data/0023/000330 data/0023/000331 data/0023/000332 data/0023/000333 data/0023/000334 data/0023/000335 data/0023/000336 data/0023/000337 data/0023/000338 data/0023/000339 data/0023/000340 data/0023/000341 data/0023/000342 data/0023/000343 data/0023/000344 data/0023/000345 data/0023/000346 data/0023/000347 data/0023/000348 data/0023/000349 data/0023/000350 data/0023/000351 data/0023/000352 data/0023/000353 data/0023/000354 data/0023/000355 data/0023/000356 data/0023/000357 data/0023/000358 data/0023/000359 data/0023/000360 data/0023/000361 data/0023/000362 data/0023/000363 data/0023/000364 data/0023/000365 data/0023/000366 data/0023/000367 data/0023/000368 data/0023/000369 data/0023/000370 data/0023/000371 data/0023/000372 data/0023/000373 data/0023/000374 data/0023/000375 data/0023/000376 data/0023/000377 data/0023/000378 data/0023/000379 data/0023/000380 data/0023/000381 data/0023/000382 data/0023/000383 data/0023/000384 data/0023/000385 data/0023/000386 data/0023/000387 data/0023/000388 data/0023/000389 data/0023/000390 data/0023/000391 data/0023/000392 data/0023/000393 data/0023/000394 data/0023/000395 data/0023/000396 data/0023/000397 data/0023/000398 data/0023/000399 data/0023/000400 data/0023/000401 data/0023/000402 data/0023/000403 data/0023/000404 data/0023/000405 data/0023/000406 data/0023/000407 data/0023/000408 data/0023/000409 data/0023/000410 data/0023/000411 data/0023/000412 data/0023/000413 data/0023/000414 data/0023/000415 data/0023/000416 data/0023/000417 data/0023/000418 data/0023/000419 data/0023/000420 data/0023/000421 data/0023/000422 data/0023/000423 data/0023/000424 data/0023/000425 data/0023/000426 data/0023/000427 data/0023/000428 data/0023/000429 data/0023/000430 data/0023/000431 data/0023/000432 data/0023/000433 data/0023/000434 data/0023/000435 data/0023/000436 data/0023/000437 data/0023/000438 data/0023/000439 data/0023/000440 data/0023/000441 data/0023/000442 data/0023/000443 data/0023/000444 data/0023/000445 data/0023/000446 data/0023/000447 data/0023/000448 data/0023/000449 data/0023/000450 data/0023/000451 data/0023/000452 data/0023/000453 data/0023/000454 data/0023/000455 data/0023/000456 data/0023/000457 data/0023/000458 data/0023/000459 data/0023/000460 data/0023/000461 data/0023/000462 data/0023/000463 data/0023/000464 data/0023/000465 data/0023/000466 data/0023/000467 data/0023/000468 data/0023/000469 data/0023/000470 data/0023/000471 data/0023/000472 data/0023/000473 data/0023/000474 data/0023/000475 data/0023/000476 data/0023/000477 data/0023/000478 data/0023/000479 data/0023/000480 data/0023/000481 data/0023/000482 data/0023/000483 data/0023/000484 data/0023/000485 data/0023/000486 data/0023/000487 data/0023/000488 data/0023/000489 data/0023/000490 data/0023/000491 data/0023/000492 data/0023/000493 data/0023/000494 data/0023/000495 data/0023/000496 data/0023/000497 data/0023/000498 data/0023/000499 data/0023/000500 data/0023/000501 data/0023/000502 data/0023/000503 data/0023/000504 data/0023/000505 data/0023/000506 data/0023/000507 data/0023/000508 data/0023/000509 data/0023/000510 data/0023/000511 data/0023/000512 data/0023/000513 data/0023/000514 data/0023/000515 data/0023/000516 data/0023/000517 data/0023/000518 data/0023/000519 data/0023/000520 data/0023/000521 data/0023/000522 data/0023/000523 data/0023/000524 data/0023/000525 data/0023/000526 data/0023/000527 data/0023/000528 data/0023/000529 data/0023/000530 data/0023/000531 data/0023/000532 data/0023/000533 data/0023/000534 data/0023/000535 data/0023/000536 data/0023/000537 data/0023/000538 data/0023/000539 data/0023/000540 data/0023/000541 data/0023/000542 data/0023/000543 data/0023/000544 data/0023/000545 data/0023/000546 data/0023/000547 data/0023/000548 data/0023/000549 data/0023/000550 data/0023/000551 data/0023/000552 data/0023/000553 data/0023/000554 data/0023/000555 data/0023/000556 data/0023/000557 data/0023/000558 data/0023/000559 data/0023/000560 data/0023/000561 data/0023/000562 data/0023/000563 data/0023/000564 data/0023/000565 data/0023/000566 data/0023/000567 data/0023/000568 data/0023/000569 data/0023/000570 data/0023/000571 data/0023/000572 data/0023/000573 data/0023/000574 data/0023/000575 data/0023/000576 data/0023/000577 data/0023/000578 data/0023/000579 data/0023/000580 data/0023/000581 data/0023/000582 data/0023/000583 data/0023/000584 data/0023/000585 data/0023/000586 data/0023/000587 data/0023/000588 data/0023/000589 data/0023/000590 data/0023/000591 data/0023/000592 data/0023/000593 data/0023/000594 data/0023/000595 data/0023/000596 data/0023/000597 data/0023/000598 data/0023/000599 data/0023/000600 data/0023/000601 data/0023/000602 data/0023/000603 data/0023/000604 data/0023/000605 data/0023/000606 data/0023/000607 data/0023/000608 data/0023/000609 data/0023/000610 data/0023/000611 data/0023/000612 data/0023/000613 data/0023/000614 data/0023/000615 data/0023/000616 data/0023/000617 data/0023/000618 data/0023/000619 data/0023/000620 data/0023/000621 data/0023/000622 data/0023/000623 data/0023/000624 data/0023/000625 data/0023/000626 data/0023/000627 data/0023/000628 data/0023/000629 data/0023/000630 data/0023/000631 data/0023/000632 data/0023/000633 data/0023/000634 data/0023/000635 data/0023/000636 data/0023/000637 data/0023/000638 data/0023/000639 data/0023/000640 data/0023/000641 data/0023/000642 data/0023/000643 data/0023/000644 data/0023/000645 data/0023/000646 data/0023/000647 data/0023/000648 data/0023/000649 data/0023/000650 data/0023/000651 data/0023/000652 data/0023/000653 data/0023/000654 data/0023/000655 data/0023/000656 data/0023/000657 data/0023/000658 data/0023/000659 data/0023/000660 data/0023/000661 data/0023/000662 data/0023/000663 data/0023/000664 data/0023/000665 data/0023/000666 data/0023/000667 data/0023/000668 data/0023/000669 data/0023/000670 data/0023/000671 data/0023/000672 data/0023/000673 data/0023/000674 data/0023/000675 data/0023/000676 data/0023/000677 data/0023/000678 data/0023/000679 data/0023/000680 data/0023/000681 data/0023/000682 data/0023/000683 data/0023/000684 data/0023/000685 data/0023/000686 data/0023/000687 data/0023/000688 data/0023/000689 data/0023/000690 data/0023/000691 data/0023/000692 data/0023/000693 data/0023/000694 data/0023/000695 data/0023/000696 data/0023/000697 data/0023/000698 data/0023/000699 data/0023/000700 data/0023/000701 data/0023/000702 data/0023/000703 data/0023/000704 data/0023/000705 data/0023/000706 data/0023/000707 data/0023/000708 data/0023/000709 data/0023/000710 data/0023/000711 data/0023/000712 data/0023/000713 data/0023/000714 data/0023/000715 data/0023/000716 data/0023/000717 data/0023/000718 data/0023/000719 data/0023/000720 data/0023/000721 data/0023/000722 data/0023/000723 data/0023/000724 data/0023/000725 data/0023/000726 data/0023/000727 data/0023/000728 data/0023/000729 data/0023/000730 data/0023/000731 data/0023/000732 data/0023/000733 data/0023/000734 data/0023/000735 data/0023/000736 data/0023/000737 data/0023/000738 data/0023/000739 data/0023/000740 data/0023/000741 data/0023/000742 data/0023/000743 data/0023/000744 data/0023/000745 data/0023/000746 data/0023/000747 data/0023/000748 data/0023/000749 data/0023/000750 data/0023/000751 data/0023/000752 data/0023/000753 data/0023/000754 data/0023/000755 data/0023/000756 data/0023/000757 data/0023/000758 data/0023/000759 data/0023/000760 data/0023/000761 data/0023/000762 data/0023/000763 data/0023/000764 data/0023/000765 data/0023/000766 data/0023/000767 data/0023/000768 data/0023/000769 data/0023/000770 data/0023/000771 data/0023/000772 data/0023/000773 data/0023/000774 data/0023/000775 data/0023/000776 data/0023/000777 data/0023/000778 data/0023/000779 data/0023/000780 data/0023/000781 data/0023/000782 data/0023/000783 data/0023/000784 data/0023/000785 data/0023/000786 data/0023/000787 data/0023/000788 data/0023/000789 data/0023/000790 data/0023/000791 data/0023/000792 data/0023/000793 data/0023/000794 data/0023/000795 data/0023/000796 data/0023/000797 data/0023/000798 data/0023/000799 data/0023/000800 data/0023/000801 data/0023/000802 data/0023/000803 data/0023/000804 data/0023/000805 data/0023/000806 data/0023/000807 data/0023/000808 data/0023/000809 data/0023/000810 data/0023/000811 data/0023/000812 data/0023/000813 data/0023/000814 data/0023/000815 data/0023/000816 data/0023/000817 data/0023/000818 data/0023/000819 data/0023/000820 data/0023/000821 data/0023/000822 data/0023/000823 data/0023/000824 data/0023/000825 data/0023/000826 data/0023/000827 data/0023/000828 data/0023/000829 data/0023/000830 data/0023/000831 data/0023/000832 data/0023/000833 data/0023/000834 data/0023/000835 data/0023/000836 data/0023/000837 data/0023/000838 data/0023/000839 data/0023/000840 data/0023/000841 data/0023/000842 data/0023/000843 data/0023/000844 data/0023/000845 data/0023/000846 data/0023/000847 data/0023/000848 data/0023/000849 data/0023/000850 data/0023/000851 data/0023/000852 data/0023/000853 data/0023/000854 data/0023/000855 data/0023/000856 data/0023/000857 data/0023/000858 data/0023/000859 data/0023/000860 data/0023/000861 data/0023/000862 data/0023/000863 data/0023/000864 data/0023/000865 data/0023/000866 data/0023/000867 data/0023/000868 data/0023/000869 data/0023/000870 data/0023/000871 data/0023/000872 data/0023/000873 data/0023/000874 data/0023/000875 data/0023/000876 data/0023/000877 data/0023/000878 data/0023/000879 data/0023/000880 data/0023/000881 data/0023/000882 data/0023/000883 data/0023/000884 data/0023/000885 data/0023/000886 data/0023/000887 data/0023/000888 data/0023/000889 data/0023/000890 data/0023/000891 data/0023/000892 data/0023/000893 data/0023/000894 data/0023/000895 data/0023/000896 data/0023/000897 data/0023/000898 data/0023/000899 data/0023/000900 data/0023/000901 data/0023/000902 data/0023/000903 data/0023/000904 data/0023/000905 data/0023/000906 data/0023/000907 data/0023/000908 data/0023/000909 data/0023/000910 data/0023/000911 data/0023/000912 data/0023/000913 data/0023/000914 data/0023/000915 data/0023/000916 data/0023/000917 data/0023/000918 data/0023/000919 data/0023/000920 data/0023/000921 data/0023/000922 data/0023/000923 data/0023/000924 data/0023/000925 data/0023/000926 data/0023/000927 data/0023/000928 data/0023/000929 data/0023/000930 data/0023/000931 data/0023/000932 data/0023/000933 data/0023/000934 data/0023/000935 data/0023/000936 data/0023/000937 data/0023/000938 data/0023/000939 data/0023/000940 data/0023/000941 data/0023/000942 data/0023/000943 data/0023/000944 data/0023/000945 data/0023/000946 data/0023/000947 data/0023/000948 data/0023/000949 data/0023/000950 data/0023/000951 data/0023/000952 data/0023/000953 data/0023/000954 data/0023/000955 data/0023/000956 data/0023/000957 data/0023/000958 data/0023/000959 data/0023/000960 data/0023/000961 data/0023/000962 data/0023/000963 data/0023/000964 data/0023/000965 data/0023/000966 data/0023/000967 data/0023/000968 data/0023/000969 data/0023/000970 data/0023/000971 data/0023/000972 data/0023/000973 data/0023/000974 data/0023/000975 data/0023/000976 data/0023/000977 data/0023/000978 data/0023/000979 data/0023/000980 data/0023/000981 data/0023/000982 data/0023/000983 data/0023/000984 data/0023/000985 data/0023/000986 data/0023/000987 data/0023/000988 data/0023/000989 data/0023/000990 data/0023/000991 data/0023/000992 data/0023/000993 data/0023/000994 data/0023/000995 data/0023/000996 data/0023/000997 data/0023/000998 data/0023/000999 data/0023/001000 data/0023/001001 data/0023/001002 data/0023/001003 data/0023/001004 data/0023/001005 data/0023/001006 data/0023/001007 data/0023/001008 data/0023/001009 data/0023/001010 data/0023/001011 data/0023/001012 data/0023/001013 data/0023/001014 data/0023/001015 data/0023/001016 data/0023/001017 data/0023/001018 data/0023/001019 data/0023/001020 data/0023/001021 data/0023/001022 data/0023/001023 data/0023/001024 data/0023/001025 data/0023/001026 data/0023/001027 data/0023/001028 data/0023/001029 data/0023/001030 data/0023/001031 data/0023/001032 data/0023/001033 data/0023/001034 data/0023/001035 data/0023/001036 data/0023/001037 data/0023/001038 data/0023/001039 data/0023/001040 data/0023/001041 data/0023/001042 data/0023/001043 data/0023/001044 data/0023/001045 data/0023/001046 data/0023/001047 data/0023/001048 data/0023/001049 data/0023/001050 data/0023/001051 data/0023/001052 data/0023/001053 data/0023/001054 data/0023/001055 data/0023/001056 data/0023/001057 data/0023/001058 data/0023/001059 data/0023/001060 data/0023/001061 data/0023/001062 data/0023/001063 data/0024/000001 data/0024/000002 data/0024/000003 data/0024/000004 data/0024/000005 data/0024/000006 data/0024/000007 data/0024/000008 data/0024/000009 data/0024/000010 data/0024/000011 data/0024/000012 data/0024/000013 data/0024/000014 data/0024/000015 data/0024/000016 data/0024/000017 data/0024/000018 data/0024/000019 data/0024/000020 data/0024/000021 data/0024/000022 data/0024/000023 data/0024/000024 data/0024/000025 data/0024/000026 data/0024/000027 data/0024/000028 data/0024/000029 data/0024/000030 data/0024/000031 data/0024/000032 data/0024/000033 data/0024/000034 data/0024/000035 data/0024/000036 data/0024/000037 data/0024/000038 data/0024/000039 data/0024/000040 data/0024/000041 data/0024/000042 data/0024/000043 data/0024/000044 data/0024/000045 data/0024/000046 data/0024/000047 data/0024/000048 data/0024/000049 data/0024/000050 data/0024/000051 data/0024/000052 data/0024/000053 data/0024/000054 data/0024/000055 data/0024/000056 data/0024/000057 data/0024/000058 data/0024/000059 data/0024/000060 data/0024/000061 data/0024/000062 data/0024/000063 data/0024/000064 data/0024/000065 data/0024/000066 data/0024/000067 data/0024/000068 data/0024/000069 data/0024/000070 data/0024/000071 data/0024/000072 data/0024/000073 data/0024/000074 data/0024/000075 data/0024/000076 data/0024/000077 data/0024/000078 data/0024/000079 data/0024/000080 data/0024/000081 data/0024/000082 data/0024/000083 data/0024/000084 data/0024/000085 data/0024/000086 data/0024/000087 data/0024/000088 data/0024/000089 data/0024/000090 data/0024/000091 data/0024/000092 data/0024/000093 data/0024/000094 data/0024/000095 data/0024/000096 data/0024/000097 data/0024/000098 data/0024/000099 data/0024/000100 data/0024/000101 data/0024/000102 data/0024/000103 data/0024/000104 data/0024/000105 data/0024/000106 data/0024/000107 data/0024/000108 data/0024/000109 data/0024/000110 data/0024/000111 data/0024/000112 data/0024/000113 data/0024/000114 data/0024/000115 data/0024/000116 data/0024/000117 data/0024/000118 data/0024/000119 data/0024/000120 data/0024/000121 data/0024/000122 data/0024/000123 data/0024/000124 data/0024/000125 data/0024/000126 data/0024/000127 data/0024/000128 data/0024/000129 data/0024/000130 data/0024/000131 data/0024/000132 data/0024/000133 data/0024/000134 data/0024/000135 data/0024/000136 data/0024/000137 data/0024/000138 data/0024/000139 data/0024/000140 data/0024/000141 data/0024/000142 data/0024/000143 data/0024/000144 data/0024/000145 data/0024/000146 data/0024/000147 data/0024/000148 data/0024/000149 data/0024/000150 data/0024/000151 data/0024/000152 data/0024/000153 data/0024/000154 data/0024/000155 data/0024/000156 data/0024/000157 data/0024/000158 data/0024/000159 data/0024/000160 data/0024/000161 data/0024/000162 data/0024/000163 data/0024/000164 data/0024/000165 data/0024/000166 data/0024/000167 data/0024/000168 data/0024/000169 data/0024/000170 data/0024/000171 data/0024/000172 data/0024/000173 data/0024/000174 data/0024/000175 data/0024/000176 data/0024/000177 data/0024/000178 data/0024/000179 data/0024/000180 data/0024/000181 data/0024/000182 data/0024/000183 data/0024/000184 data/0024/000185 data/0024/000186 data/0024/000187 data/0024/000188 data/0024/000189 data/0024/000190 data/0024/000191 data/0024/000192 data/0024/000193 data/0024/000194 data/0024/000195 data/0024/000196 data/0024/000197 data/0024/000198 data/0024/000199 data/0024/000200 data/0024/000201 data/0024/000202 data/0024/000203 data/0024/000204 data/0024/000205 data/0024/000206 data/0024/000207 data/0024/000208 data/0024/000209 data/0024/000210 data/0024/000211 data/0024/000212 data/0024/000213 data/0024/000214 data/0024/000215 data/0024/000216 data/0024/000217 data/0024/000218 data/0024/000219 data/0024/000220 data/0024/000221 data/0024/000222 data/0024/000223 data/0024/000224 data/0024/000225 data/0024/000226 data/0024/000227 data/0024/000228 data/0024/000229 data/0024/000230 data/0024/000231 data/0024/000232 data/0024/000233 data/0024/000234 data/0024/000235 data/0024/000236 data/0024/000237 data/0024/000238 data/0024/000239 data/0024/000240 data/0024/000241 data/0024/000242 data/0024/000243 data/0024/000244 data/0024/000245 data/0024/000246 data/0024/000247 data/0024/000248 data/0024/000249 data/0024/000250 data/0024/000251 data/0024/000252 data/0024/000253 data/0024/000254 data/0024/000255 data/0024/000256 data/0024/000257 data/0024/000258 data/0024/000259 data/0024/000260 data/0024/000261 data/0024/000262 data/0024/000263 data/0024/000264 data/0024/000265 data/0024/000266 data/0024/000267 data/0024/000268 data/0024/000269 data/0024/000270 data/0024/000271 data/0024/000272 data/0024/000273 data/0024/000274 data/0024/000275 data/0024/000276 data/0024/000277 data/0024/000278 data/0024/000279 data/0024/000280 data/0024/000281 data/0024/000282 data/0024/000283 data/0024/000284 data/0024/000285 data/0024/000286 data/0024/000287 data/0024/000288 data/0024/000289 data/0024/000290 data/0024/000291 data/0024/000292 data/0024/000293 data/0024/000294 data/0024/000295 data/0024/000296 data/0024/000297 data/0024/000298 data/0024/000299 data/0024/000300 data/0024/000301 data/0024/000302 data/0024/000303 data/0024/000304 data/0024/000305 data/0024/000306 data/0024/000307 data/0024/000308 data/0024/000309 data/0024/000310 data/0024/000311 data/0024/000312 data/0024/000313 data/0024/000314 data/0024/000315 data/0024/000316 data/0024/000317 data/0024/000318 data/0024/000319 data/0024/000320 data/0024/000321 data/0024/000322 data/0024/000323 data/0024/000324 data/0024/000325 data/0024/000326 data/0024/000327 data/0024/000328 data/0024/000329 data/0024/000330 data/0024/000331 data/0024/000332 data/0024/000333 data/0024/000334 data/0024/000335 data/0024/000336 data/0024/000337 data/0024/000338 data/0024/000339 data/0024/000340 data/0024/000341 data/0024/000342 data/0024/000343 data/0024/000344 data/0024/000345 data/0024/000346 data/0024/000347 data/0024/000348 data/0024/000349 data/0024/000350 data/0024/000351 data/0024/000352 data/0024/000353 data/0024/000354 data/0024/000355 data/0024/000356 data/0024/000357 data/0024/000358 data/0024/000359 data/0024/000360 data/0024/000361 data/0024/000362 data/0024/000363 data/0024/000364 data/0024/000365 data/0024/000366 data/0024/000367 data/0024/000368 data/0024/000369 data/0024/000370 data/0024/000371 data/0024/000372 data/0024/000373 data/0024/000374 data/0024/000375 data/0024/000376 data/0024/000377 data/0024/000378 data/0024/000379 data/0024/000380 data/0024/000381 data/0024/000382 data/0024/000383 data/0024/000384 data/0024/000385 data/0024/000386 data/0024/000387 data/0024/000388 data/0024/000389 data/0024/000390 data/0024/000391 data/0024/000392 data/0024/000393 data/0024/000394 data/0024/000395 data/0024/000396 data/0024/000397 data/0024/000398 data/0024/000399 data/0024/000400 data/0024/000401 data/0024/000402 data/0024/000403 data/0024/000404 data/0024/000405 data/0024/000406 data/0024/000407 data/0024/000408 data/0024/000409 data/0024/000410 data/0024/000411 data/0024/000412 data/0024/000413 data/0024/000414 data/0024/000415 data/0024/000416 data/0024/000417 data/0024/000418 data/0024/000419 data/0024/000420 data/0024/000421 data/0024/000422 data/0024/000423 data/0024/000424 data/0024/000425 data/0024/000426 data/0024/000427 data/0024/000428 data/0024/000429 data/0024/000430 data/0024/000431 data/0024/000432 data/0024/000433 data/0024/000434 data/0024/000435 data/0024/000436 data/0024/000437 data/0024/000438 data/0024/000439 data/0024/000440 data/0024/000441 data/0024/000442 data/0024/000443 data/0024/000444 data/0024/000445 data/0024/000446 data/0024/000447 data/0024/000448 data/0024/000449 data/0024/000450 data/0024/000451 data/0024/000452 data/0024/000453 data/0024/000454 data/0024/000455 data/0024/000456 data/0024/000457 data/0024/000458 data/0024/000459 data/0024/000460 data/0024/000461 data/0024/000462 data/0024/000463 data/0024/000464 data/0024/000465 data/0024/000466 data/0024/000467 data/0024/000468 data/0024/000469 data/0024/000470 data/0024/000471 data/0024/000472 data/0024/000473 data/0024/000474 data/0024/000475 data/0024/000476 data/0024/000477 data/0024/000478 data/0024/000479 data/0024/000480 data/0024/000481 data/0024/000482 data/0024/000483 data/0024/000484 data/0024/000485 data/0024/000486 data/0024/000487 data/0024/000488 data/0024/000489 data/0024/000490 data/0024/000491 data/0024/000492 data/0024/000493 data/0024/000494 data/0024/000495 data/0024/000496 data/0024/000497 data/0024/000498 data/0024/000499 data/0024/000500 data/0024/000501 data/0024/000502 data/0024/000503 data/0024/000504 data/0024/000505 data/0024/000506 data/0024/000507 data/0024/000508 data/0024/000509 data/0024/000510 data/0024/000511 data/0024/000512 data/0024/000513 data/0024/000514 data/0024/000515 data/0024/000516 data/0024/000517 data/0024/000518 data/0024/000519 data/0024/000520 data/0024/000521 data/0024/000522 data/0024/000523 data/0024/000524 data/0024/000525 data/0024/000526 data/0024/000527 data/0024/000528 data/0024/000529 data/0024/000530 data/0024/000531 data/0024/000532 data/0024/000533 data/0024/000534 data/0024/000535 data/0024/000536 data/0024/000537 data/0024/000538 data/0024/000539 data/0024/000540 data/0024/000541 data/0024/000542 data/0024/000543 data/0024/000544 data/0024/000545 data/0024/000546 data/0024/000547 data/0024/000548 data/0024/000549 data/0024/000550 data/0024/000551 data/0024/000552 data/0024/000553 data/0024/000554 data/0024/000555 data/0024/000556 data/0024/000557 data/0024/000558 data/0024/000559 data/0024/000560 data/0024/000561 data/0024/000562 data/0024/000563 data/0024/000564 data/0024/000565 data/0024/000566 data/0024/000567 data/0024/000568 data/0024/000569 data/0024/000570 data/0024/000571 data/0024/000572 data/0024/000573 data/0024/000574 data/0024/000575 data/0024/000576 data/0024/000577 data/0024/000578 data/0024/000579 data/0024/000580 data/0024/000581 data/0024/000582 data/0024/000583 data/0024/000584 data/0024/000585 data/0024/000586 data/0024/000587 data/0024/000588 data/0024/000589 data/0024/000590 data/0024/000591 data/0024/000592 data/0024/000593 data/0024/000594 data/0024/000595 data/0024/000596 data/0024/000597 data/0024/000598 data/0024/000599 data/0024/000600 data/0024/000601 data/0024/000602 data/0024/000603 data/0024/000604 data/0024/000605 data/0024/000606 data/0024/000607 data/0024/000608 data/0024/000609 data/0024/000610 data/0024/000611 data/0024/000612 data/0024/000613 data/0024/000614 data/0024/000615 data/0024/000616 data/0024/000617 data/0024/000618 data/0024/000619 data/0024/000620 data/0024/000621 data/0024/000622 data/0024/000623 data/0024/000624 data/0024/000625 data/0024/000626 data/0024/000627 data/0024/000628 data/0024/000629 data/0024/000630 data/0024/000631 data/0024/000632 data/0024/000633 data/0024/000634 data/0024/000635 data/0024/000636 data/0024/000637 data/0024/000638 data/0024/000639 data/0024/000640 data/0024/000641 data/0024/000642 data/0024/000643 data/0024/000644 data/0024/000645 data/0024/000646 data/0024/000647 data/0024/000648 data/0024/000649 data/0024/000650 data/0024/000651 data/0024/000652 data/0024/000653 data/0024/000654 data/0024/000655 data/0024/000656 data/0024/000657 data/0024/000658 data/0024/000659 data/0024/000660 data/0024/000661 data/0024/000662 data/0024/000663 data/0024/000664 data/0024/000665 data/0024/000666 data/0024/000667 data/0024/000668 data/0024/000669 data/0024/000670 data/0024/000671 data/0024/000672 data/0024/000673 data/0024/000674 data/0024/000675 data/0024/000676 data/0024/000677 data/0024/000678 data/0024/000679 data/0024/000680 data/0024/000681 data/0024/000682 data/0024/000683 data/0024/000684 data/0024/000685 data/0024/000686 data/0024/000687 data/0024/000688 data/0024/000689 data/0024/000690 data/0024/000691 data/0024/000692 data/0024/000693 data/0024/000694 data/0024/000695 data/0024/000696 data/0024/000697 data/0024/000698 data/0024/000699 data/0024/000700 data/0024/000701 data/0024/000702 data/0024/000703 data/0024/000704 data/0024/000705 data/0024/000706 data/0024/000707 data/0024/000708 data/0024/000709 data/0024/000710 data/0024/000711 data/0024/000712 data/0024/000713 data/0024/000714 data/0024/000715 data/0024/000716 data/0024/000717 data/0024/000718 data/0024/000719 data/0024/000720 data/0024/000721 data/0024/000722 data/0024/000723 data/0024/000724 data/0024/000725 data/0024/000726 data/0024/000727 data/0024/000728 data/0024/000729 data/0024/000730 data/0024/000731 data/0024/000732 data/0024/000733 data/0024/000734 data/0024/000735 data/0024/000736 data/0024/000737 data/0024/000738 data/0024/000739 data/0024/000740 data/0024/000741 data/0024/000742 data/0024/000743 data/0024/000744 data/0024/000745 data/0024/000746 data/0024/000747 data/0024/000748 data/0024/000749 data/0024/000750 data/0024/000751 data/0024/000752 data/0024/000753 data/0024/000754 data/0024/000755 data/0024/000756 data/0024/000757 data/0024/000758 data/0024/000759 data/0024/000760 data/0024/000761 data/0024/000762 data/0024/000763 data/0024/000764 data/0024/000765 data/0024/000766 data/0024/000767 data/0024/000768 data/0024/000769 data/0024/000770 data/0024/000771 data/0024/000772 data/0024/000773 data/0024/000774 data/0024/000775 data/0024/000776 data/0024/000777 data/0024/000778 data/0024/000779 data/0024/000780 data/0024/000781 data/0024/000782 data/0024/000783 data/0024/000784 data/0024/000785 data/0024/000786 data/0024/000787 data/0024/000788 data/0024/000789 data/0024/000790 data/0024/000791 data/0024/000792 data/0024/000793 data/0024/000794 data/0024/000795 data/0024/000796 data/0024/000797 data/0024/000798 data/0024/000799 data/0024/000800 data/0024/000801 data/0024/000802 data/0024/000803 data/0024/000804 data/0024/000805 data/0024/000806 data/0024/000807 data/0024/000808 data/0024/000809 data/0024/000810 data/0024/000811 data/0024/000812 data/0024/000813 data/0024/000814 data/0024/000815 data/0024/000816 data/0024/000817 data/0024/000818 data/0024/000819 data/0024/000820 data/0024/000821 data/0024/000822 data/0024/000823 data/0024/000824 data/0024/000825 data/0024/000826 data/0024/000827 data/0024/000828 data/0024/000829 data/0024/000830 data/0024/000831 data/0024/000832 data/0024/000833 data/0024/000834 data/0024/000835 data/0024/000836 data/0024/000837 data/0024/000838 data/0024/000839 data/0024/000840 data/0024/000841 data/0024/000842 data/0024/000843 data/0024/000844 data/0024/000845 data/0024/000846 data/0024/000847 data/0024/000848 data/0024/000849 data/0024/000850 data/0024/000851 data/0024/000852 data/0024/000853 data/0024/000854 data/0024/000855 data/0024/000856 data/0024/000857 data/0024/000858 data/0024/000859 data/0024/000860 data/0024/000861 data/0024/000862 data/0024/000863 data/0024/000864 data/0024/000865 data/0024/000866 data/0024/000867 data/0024/000868 data/0024/000869 data/0024/000870 data/0024/000871 data/0024/000872 data/0024/000873 data/0024/000874 data/0024/000875 data/0024/000876 data/0024/000877 data/0024/000878 data/0024/000879 data/0024/000880 data/0024/000881 data/0024/000882 data/0024/000883 data/0024/000884 data/0024/000885 data/0024/000886 data/0024/000887 data/0024/000888 data/0024/000889 data/0024/000890 data/0024/000891 data/0024/000892 data/0024/000893 data/0024/000894 data/0024/000895 data/0024/000896 data/0024/000897 data/0024/000898 data/0024/000899 data/0024/000900 data/0024/000901 data/0024/000902 data/0024/000903 data/0024/000904 data/0024/000905 data/0024/000906 data/0024/000907 data/0024/000908 data/0024/000909 data/0024/000910 data/0024/000911 data/0024/000912 data/0024/000913 data/0024/000914 data/0024/000915 data/0024/000916 data/0024/000917 data/0024/000918 data/0024/000919 data/0024/000920 data/0024/000921 data/0024/000922 data/0024/000923 data/0024/000924 data/0024/000925 data/0024/000926 data/0024/000927 data/0024/000928 data/0024/000929 data/0024/000930 data/0024/000931 data/0024/000932 data/0024/000933 data/0024/000934 data/0024/000935 data/0024/000936 data/0024/000937 data/0024/000938 data/0024/000939 data/0024/000940 data/0024/000941 data/0024/000942 data/0024/000943 data/0024/000944 data/0024/000945 data/0024/000946 data/0024/000947 data/0024/000948 data/0024/000949 data/0024/000950 data/0024/000951 data/0024/000952 data/0024/000953 data/0024/000954 data/0024/000955 data/0024/000956 data/0024/000957 data/0024/000958 data/0024/000959 data/0024/000960 data/0024/000961 data/0024/000962 data/0024/000963 data/0024/000964 data/0024/000965 data/0024/000966 data/0024/000967 data/0024/000968 data/0024/000969 data/0024/000970 data/0033/000001 data/0033/000002 data/0033/000003 data/0033/000004 data/0033/000005 data/0033/000006 data/0033/000007 data/0033/000008 data/0033/000009 data/0033/000010 data/0033/000011 data/0033/000012 data/0033/000013 data/0033/000014 data/0033/000015 data/0033/000016 data/0033/000017 data/0033/000018 data/0033/000019 data/0033/000020 data/0033/000021 data/0033/000022 data/0033/000023 data/0033/000024 data/0033/000025 data/0033/000026 data/0033/000027 data/0033/000028 data/0033/000029 data/0033/000030 data/0033/000031 data/0033/000032 data/0033/000033 data/0033/000034 data/0033/000035 data/0033/000036 data/0033/000037 data/0033/000038 data/0033/000039 data/0033/000040 data/0033/000041 data/0033/000042 data/0033/000043 data/0033/000044 data/0033/000045 data/0033/000046 data/0033/000047 data/0033/000048 data/0033/000049 data/0033/000050 data/0033/000051 data/0033/000052 data/0033/000053 data/0033/000054 data/0033/000055 data/0033/000056 data/0033/000057 data/0033/000058 data/0033/000059 data/0033/000060 data/0033/000061 data/0033/000062 data/0033/000063 data/0033/000064 data/0033/000065 data/0033/000066 data/0033/000067 data/0033/000068 data/0033/000069 data/0033/000070 data/0033/000071 data/0033/000072 data/0033/000073 data/0033/000074 data/0033/000075 data/0033/000076 data/0033/000077 data/0033/000078 data/0033/000079 data/0033/000080 data/0033/000081 data/0033/000082 data/0033/000083 data/0033/000084 data/0033/000085 data/0033/000086 data/0033/000087 data/0033/000088 data/0033/000089 data/0033/000090 data/0033/000091 data/0033/000092 data/0033/000093 data/0033/000094 data/0033/000095 data/0033/000096 data/0033/000097 data/0033/000098 data/0033/000099 data/0033/000100 data/0033/000101 data/0033/000102 data/0033/000103 data/0033/000104 data/0033/000105 data/0033/000106 data/0033/000107 data/0033/000108 data/0033/000109 data/0033/000110 data/0033/000111 data/0033/000112 data/0033/000113 data/0033/000114 data/0033/000115 data/0033/000116 data/0033/000117 data/0033/000118 data/0033/000119 data/0033/000120 data/0033/000121 data/0033/000122 data/0033/000123 data/0033/000124 data/0033/000125 data/0033/000126 data/0033/000127 data/0033/000128 data/0033/000129 data/0033/000130 data/0033/000131 data/0033/000132 data/0033/000133 data/0033/000134 data/0033/000135 data/0033/000136 data/0033/000137 data/0033/000138 data/0033/000139 data/0033/000140 data/0033/000141 data/0033/000142 data/0033/000143 data/0033/000144 data/0033/000145 data/0033/000146 data/0033/000147 data/0033/000148 data/0033/000149 data/0033/000150 data/0033/000151 data/0033/000152 data/0033/000153 data/0033/000154 data/0033/000155 data/0033/000156 data/0033/000157 data/0033/000158 data/0033/000159 data/0033/000160 data/0033/000161 data/0033/000162 data/0033/000163 data/0033/000164 data/0033/000165 data/0033/000166 data/0033/000167 data/0033/000168 data/0033/000169 data/0033/000170 data/0033/000171 data/0033/000172 data/0033/000173 data/0033/000174 data/0033/000175 data/0033/000176 data/0033/000177 data/0033/000178 data/0033/000179 data/0033/000180 data/0033/000181 data/0033/000182 data/0033/000183 data/0033/000184 data/0033/000185 data/0033/000186 data/0033/000187 data/0033/000188 data/0033/000189 data/0033/000190 data/0033/000191 data/0033/000192 data/0033/000193 data/0033/000194 data/0033/000195 data/0033/000196 data/0033/000197 data/0033/000198 data/0033/000199 data/0033/000200 data/0033/000201 data/0033/000202 data/0033/000203 data/0033/000204 data/0033/000205 data/0033/000206 data/0033/000207 data/0033/000208 data/0033/000209 data/0033/000210 data/0033/000211 data/0033/000212 data/0033/000213 data/0033/000214 data/0033/000215 data/0033/000216 data/0033/000217 data/0033/000218 data/0033/000219 data/0033/000220 data/0033/000221 data/0033/000222 data/0033/000223 data/0033/000224 data/0033/000225 data/0033/000226 data/0033/000227 data/0033/000228 data/0033/000229 data/0033/000230 data/0033/000231 data/0033/000232 data/0033/000233 data/0033/000234 data/0033/000235 data/0033/000236 data/0033/000237 data/0033/000238 data/0033/000239 data/0033/000240 data/0033/000241 data/0033/000242 data/0033/000243 data/0033/000244 data/0033/000245 data/0033/000246 data/0033/000247 data/0033/000248 data/0033/000249 data/0033/000250 data/0033/000251 data/0033/000252 data/0033/000253 data/0033/000254 data/0033/000255 data/0033/000256 data/0033/000257 data/0033/000258 data/0033/000259 data/0033/000260 data/0033/000261 data/0033/000262 data/0033/000263 data/0033/000264 data/0033/000265 data/0033/000266 data/0033/000267 data/0033/000268 data/0033/000269 data/0033/000270 data/0033/000271 data/0033/000272 data/0033/000273 data/0033/000274 data/0033/000275 data/0033/000276 data/0033/000277 data/0033/000278 data/0033/000279 data/0033/000280 data/0033/000281 data/0033/000282 data/0033/000283 data/0033/000284 data/0033/000285 data/0033/000286 data/0033/000287 data/0033/000288 data/0033/000289 data/0033/000290 data/0033/000291 data/0033/000292 data/0033/000293 data/0033/000294 data/0033/000295 data/0033/000296 data/0033/000297 data/0033/000298 data/0033/000299 data/0033/000300 data/0033/000301 data/0033/000302 data/0033/000303 data/0033/000304 data/0033/000305 data/0033/000306 data/0033/000307 data/0033/000308 data/0033/000309 data/0033/000310 data/0033/000311 data/0033/000312 data/0033/000313 data/0033/000314 data/0033/000315 data/0033/000316 data/0033/000317 data/0033/000318 data/0033/000319 data/0033/000320 data/0033/000321 data/0033/000322 data/0033/000323 data/0033/000324 data/0033/000325 data/0033/000326 data/0033/000327 data/0033/000328 data/0033/000329 data/0033/000330 data/0033/000331 data/0033/000332 data/0033/000333 data/0033/000334 data/0033/000335 data/0033/000336 data/0033/000337 data/0033/000338 data/0033/000339 data/0033/000340 data/0033/000341 data/0033/000342 data/0033/000343 data/0033/000344 data/0033/000345 data/0033/000346 data/0033/000347 data/0033/000348 data/0033/000349 data/0033/000350 data/0033/000351 data/0033/000352 data/0033/000353 data/0033/000354 data/0033/000355 data/0033/000356 data/0033/000357 data/0033/000358 data/0033/000359 data/0033/000360 data/0033/000361 data/0033/000362 data/0033/000363 data/0033/000364 data/0033/000365 data/0033/000366 data/0033/000367 data/0033/000368 data/0033/000369 data/0033/000370 data/0033/000371 data/0033/000372 data/0033/000373 data/0033/000374 data/0033/000375 data/0033/000376 data/0033/000377 data/0033/000378 data/0033/000379 data/0033/000380 data/0033/000381 data/0033/000382 data/0033/000383 data/0033/000384 data/0033/000385 data/0033/000386 data/0033/000387 data/0033/000388 data/0033/000389 data/0033/000390 data/0033/000391 data/0033/000392 data/0033/000393 data/0033/000394 data/0033/000395 data/0033/000396 data/0033/000397 data/0033/000398 data/0033/000399 data/0033/000400 data/0033/000401 data/0033/000402 data/0033/000403 data/0033/000404 data/0033/000405 data/0033/000406 data/0033/000407 data/0033/000408 data/0033/000409 data/0033/000410 data/0033/000411 data/0033/000412 data/0033/000413 data/0033/000414 data/0033/000415 data/0033/000416 data/0033/000417 data/0033/000418 data/0033/000419 data/0033/000420 data/0033/000421 data/0033/000422 data/0033/000423 data/0033/000424 data/0033/000425 data/0033/000426 data/0033/000427 data/0033/000428 data/0033/000429 data/0033/000430 data/0033/000431 data/0033/000432 data/0033/000433 data/0033/000434 data/0033/000435 data/0033/000436 data/0033/000437 data/0033/000438 data/0033/000439 data/0033/000440 data/0033/000441 data/0033/000442 data/0033/000443 data/0033/000444 data/0033/000445 data/0033/000446 data/0033/000447 data/0033/000448 data/0033/000449 data/0033/000450 data/0033/000451 data/0033/000452 data/0033/000453 data/0033/000454 data/0033/000455 data/0033/000456 data/0033/000457 data/0033/000458 data/0033/000459 data/0033/000460 data/0033/000461 data/0033/000462 data/0033/000463 data/0033/000464 data/0033/000465 data/0033/000466 data/0033/000467 data/0033/000468 data/0033/000469 data/0033/000470 data/0033/000471 data/0033/000472 data/0033/000473 data/0033/000474 data/0033/000475 data/0033/000476 data/0033/000477 data/0033/000478 data/0033/000479 data/0033/000480 data/0033/000481 data/0033/000482 data/0033/000483 data/0033/000484 data/0033/000485 data/0033/000486 data/0033/000487 data/0033/000488 data/0033/000489 data/0033/000490 data/0033/000491 data/0033/000492 data/0033/000493 data/0033/000494 data/0033/000495 data/0033/000496 data/0033/000497 data/0033/000498 data/0033/000499 data/0033/000500 data/0033/000501 data/0033/000502 data/0033/000503 data/0033/000504 data/0033/000505 data/0033/000506 data/0033/000507 data/0033/000508 data/0033/000509 data/0033/000510 data/0033/000511 data/0033/000512 data/0033/000513 data/0033/000514 data/0033/000515 data/0033/000516 data/0033/000517 data/0033/000518 data/0033/000519 data/0033/000520 data/0033/000521 data/0033/000522 data/0033/000523 data/0033/000524 data/0033/000525 data/0033/000526 data/0033/000527 data/0033/000528 data/0033/000529 data/0033/000530 data/0033/000531 data/0033/000532 data/0033/000533 data/0033/000534 data/0033/000535 data/0033/000536 data/0033/000537 data/0033/000538 data/0033/000539 data/0033/000540 data/0033/000541 data/0033/000542 data/0033/000543 data/0033/000544 data/0033/000545 data/0033/000546 data/0033/000547 data/0033/000548 data/0033/000549 data/0033/000550 data/0033/000551 data/0033/000552 data/0033/000553 data/0033/000554 data/0033/000555 data/0033/000556 data/0033/000557 data/0033/000558 data/0033/000559 data/0033/000560 data/0033/000561 data/0033/000562 data/0033/000563 data/0033/000564 data/0033/000565 data/0033/000566 data/0033/000567 data/0033/000568 data/0033/000569 data/0033/000570 data/0033/000571 data/0033/000572 data/0033/000573 data/0033/000574 data/0033/000575 data/0033/000576 data/0033/000577 data/0033/000578 data/0033/000579 data/0033/000580 data/0033/000581 data/0033/000582 data/0033/000583 data/0033/000584 data/0033/000585 data/0033/000586 data/0033/000587 data/0033/000588 data/0033/000589 data/0033/000590 data/0033/000591 data/0033/000592 data/0033/000593 data/0033/000594 data/0033/000595 data/0033/000596 data/0033/000597 data/0033/000598 data/0033/000599 data/0033/000600 data/0033/000601 data/0033/000602 data/0033/000603 data/0033/000604 data/0033/000605 data/0033/000606 data/0033/000607 data/0033/000608 data/0033/000609 data/0033/000610 data/0033/000611 data/0033/000612 data/0033/000613 data/0033/000614 data/0033/000615 data/0033/000616 data/0033/000617 data/0033/000618 data/0033/000619 data/0033/000620 data/0033/000621 data/0033/000622 data/0033/000623 data/0033/000624 data/0033/000625 data/0033/000626 data/0033/000627 data/0033/000628 data/0033/000629 data/0033/000630 data/0033/000631 data/0033/000632 data/0033/000633 data/0033/000634 data/0033/000635 data/0033/000636 data/0033/000637 data/0033/000638 data/0033/000639 data/0033/000640 data/0033/000641 data/0033/000642 data/0033/000643 data/0033/000644 data/0033/000645 data/0033/000646 data/0033/000647 data/0033/000648 data/0033/000649 data/0033/000650 data/0033/000651 data/0033/000652 data/0033/000653 data/0033/000654 data/0033/000655 data/0033/000656 data/0033/000657 data/0033/000658 data/0033/000659 data/0033/000660 data/0033/000661 data/0033/000662 data/0033/000663 data/0033/000664 data/0033/000665 data/0033/000666 data/0033/000667 data/0033/000668 data/0033/000669 data/0033/000670 data/0033/000671 data/0033/000672 data/0033/000673 data/0033/000674 data/0033/000675 data/0033/000676 data/0033/000677 data/0033/000678 data/0033/000679 data/0033/000680 data/0033/000681 data/0033/000682 data/0033/000683 data/0033/000684 data/0033/000685 data/0033/000686 data/0033/000687 data/0033/000688 data/0033/000689 data/0033/000690 data/0033/000691 data/0033/000692 data/0033/000693 data/0033/000694 data/0033/000695 data/0033/000696 data/0033/000697 data/0033/000698 data/0033/000699 data/0033/000700 data/0033/000701 data/0033/000702 data/0033/000703 data/0033/000704 data/0033/000705 data/0033/000706 data/0033/000707 data/0033/000708 data/0033/000709 data/0033/000710 data/0033/000711 data/0033/000712 data/0033/000713 data/0033/000714 data/0033/000715 data/0033/000716 data/0033/000717 data/0033/000718 data/0033/000719 data/0033/000720 data/0033/000721 data/0033/000722 data/0033/000723 data/0033/000724 data/0033/000725 data/0033/000726 data/0033/000727 data/0033/000728 data/0033/000729 data/0033/000730 data/0033/000731 data/0033/000732 data/0033/000733 data/0033/000734 data/0033/000735 data/0033/000736 data/0033/000737 data/0033/000738 data/0033/000739 data/0033/000740 data/0033/000741 data/0033/000742 data/0033/000743 data/0033/000744 data/0033/000745 data/0033/000746 data/0033/000747 data/0033/000748 data/0033/000749 data/0033/000750 data/0033/000751 data/0033/000752 data/0033/000753 data/0033/000754 data/0033/000755 data/0033/000756 data/0033/000757 data/0033/000758 data/0033/000759 data/0033/000760 data/0033/000761 data/0033/000762 data/0033/000763 data/0033/000764 data/0033/000765 data/0033/000766 data/0033/000767 data/0033/000768 data/0033/000769 data/0033/000770 data/0033/000771 data/0033/000772 data/0033/000773 data/0033/000774 data/0033/000775 data/0033/000776 data/0033/000777 data/0033/000778 data/0033/000779 data/0033/000780 data/0033/000781 data/0033/000782 data/0033/000783 data/0033/000784 data/0033/000785 data/0033/000786 data/0033/000787 data/0033/000788 data/0033/000789 data/0033/000790 data/0033/000791 data/0034/000001 data/0034/000002 data/0034/000003 data/0034/000004 data/0034/000005 data/0034/000006 data/0034/000007 data/0034/000008 data/0034/000009 data/0034/000010 data/0034/000011 data/0034/000012 data/0034/000013 data/0034/000014 data/0034/000015 data/0034/000016 data/0034/000017 data/0034/000018 data/0034/000019 data/0034/000020 data/0034/000021 data/0034/000022 data/0034/000023 data/0034/000024 data/0034/000025 data/0034/000026 data/0034/000027 data/0034/000028 data/0034/000029 data/0034/000030 data/0034/000031 data/0034/000032 data/0034/000033 data/0034/000034 data/0034/000035 data/0034/000036 data/0034/000037 data/0034/000038 data/0034/000039 data/0034/000040 data/0034/000041 data/0034/000042 data/0034/000043 data/0034/000044 data/0034/000045 data/0034/000046 data/0034/000047 data/0034/000048 data/0034/000049 data/0034/000050 data/0034/000051 data/0034/000052 data/0034/000053 data/0034/000054 data/0034/000055 data/0034/000056 data/0034/000057 data/0034/000058 data/0034/000059 data/0034/000060 data/0034/000061 data/0034/000062 data/0034/000063 data/0034/000064 data/0034/000065 data/0034/000066 data/0034/000067 data/0034/000068 data/0034/000069 data/0034/000070 data/0034/000071 data/0034/000072 data/0034/000073 data/0034/000074 data/0034/000075 data/0034/000076 data/0034/000077 data/0034/000078 data/0034/000079 data/0034/000080 data/0034/000081 data/0034/000082 data/0034/000083 data/0034/000084 data/0034/000085 data/0034/000086 data/0034/000087 data/0034/000088 data/0034/000089 data/0034/000090 data/0034/000091 data/0034/000092 data/0034/000093 data/0034/000094 data/0034/000095 data/0034/000096 data/0034/000097 data/0034/000098 data/0034/000099 data/0034/000100 data/0034/000101 data/0034/000102 data/0034/000103 data/0034/000104 data/0034/000105 data/0034/000106 data/0034/000107 data/0034/000108 data/0034/000109 data/0034/000110 data/0034/000111 data/0034/000112 data/0034/000113 data/0034/000114 data/0034/000115 data/0034/000116 data/0034/000117 data/0034/000118 data/0034/000119 data/0034/000120 data/0034/000121 data/0034/000122 data/0034/000123 data/0034/000124 data/0034/000125 data/0034/000126 data/0034/000127 data/0034/000128 data/0034/000129 data/0034/000130 data/0034/000131 data/0034/000132 data/0034/000133 data/0034/000134 data/0034/000135 data/0034/000136 data/0034/000137 data/0034/000138 data/0034/000139 data/0034/000140 data/0034/000141 data/0034/000142 data/0034/000143 data/0034/000144 data/0034/000145 data/0034/000146 data/0034/000147 data/0034/000148 data/0034/000149 data/0034/000150 data/0034/000151 data/0034/000152 data/0034/000153 data/0034/000154 data/0034/000155 data/0034/000156 data/0034/000157 data/0034/000158 data/0034/000159 data/0034/000160 data/0034/000161 data/0034/000162 data/0034/000163 data/0034/000164 data/0034/000165 data/0034/000166 data/0034/000167 data/0034/000168 data/0034/000169 data/0034/000170 data/0034/000171 data/0034/000172 data/0034/000173 data/0034/000174 data/0034/000175 data/0034/000176 data/0034/000177 data/0034/000178 data/0034/000179 data/0034/000180 data/0034/000181 data/0034/000182 data/0034/000183 data/0034/000184 data/0034/000185 data/0034/000186 data/0034/000187 data/0034/000188 data/0034/000189 data/0034/000190 data/0034/000191 data/0034/000192 data/0034/000193 data/0034/000194 data/0034/000195 data/0034/000196 data/0034/000197 data/0034/000198 data/0034/000199 data/0034/000200 data/0034/000201 data/0034/000202 data/0034/000203 data/0034/000204 data/0034/000205 data/0034/000206 data/0034/000207 data/0034/000208 data/0034/000209 data/0034/000210 data/0034/000211 data/0034/000212 data/0034/000213 data/0034/000214 data/0034/000215 data/0034/000216 data/0034/000217 data/0034/000218 data/0034/000219 data/0034/000220 data/0034/000221 data/0034/000222 data/0034/000223 data/0034/000224 data/0034/000225 data/0034/000226 data/0034/000227 data/0034/000228 data/0034/000229 data/0034/000230 data/0034/000231 data/0034/000232 data/0034/000233 data/0034/000234 data/0034/000235 data/0034/000236 data/0034/000237 data/0034/000238 data/0034/000239 data/0034/000240 data/0034/000241 data/0034/000242 data/0034/000243 data/0034/000244 data/0034/000245 data/0034/000246 data/0034/000247 data/0034/000248 data/0034/000249 data/0034/000250 data/0034/000251 data/0034/000252 data/0034/000253 data/0034/000254 data/0034/000255 data/0034/000256 data/0034/000257 data/0034/000258 data/0034/000259 data/0034/000260 data/0034/000261 data/0034/000262 data/0034/000263 data/0034/000264 data/0034/000265 data/0034/000266 data/0034/000267 data/0034/000268 data/0034/000269 data/0034/000270 data/0034/000271 data/0034/000272 data/0034/000273 data/0034/000274 data/0034/000275 data/0034/000276 data/0034/000277 data/0034/000278 data/0034/000279 data/0034/000280 data/0034/000281 data/0034/000282 data/0034/000283 data/0034/000284 data/0034/000285 data/0034/000286 data/0034/000287 data/0034/000288 data/0034/000289 data/0034/000290 data/0034/000291 data/0034/000292 data/0034/000293 data/0034/000294 data/0034/000295 data/0034/000296 data/0034/000297 data/0034/000298 data/0034/000299 data/0034/000300 data/0034/000301 data/0034/000302 data/0034/000303 data/0034/000304 data/0034/000305 data/0034/000306 data/0034/000307 data/0034/000308 data/0034/000309 data/0034/000310 data/0034/000311 data/0034/000312 data/0034/000313 data/0034/000314 data/0034/000315 data/0034/000316 data/0034/000317 data/0034/000318 data/0034/000319 data/0034/000320 data/0034/000321 data/0034/000322 data/0034/000323 data/0034/000324 data/0034/000325 data/0034/000326 data/0034/000327 data/0034/000328 data/0034/000329 data/0034/000330 data/0034/000331 data/0034/000332 data/0034/000333 data/0034/000334 data/0034/000335 data/0034/000336 data/0034/000337 data/0034/000338 data/0034/000339 data/0034/000340 data/0034/000341 data/0034/000342 data/0034/000343 data/0034/000344 data/0034/000345 data/0034/000346 data/0034/000347 data/0034/000348 data/0034/000349 data/0034/000350 data/0034/000351 data/0034/000352 data/0034/000353 data/0034/000354 data/0034/000355 data/0034/000356 data/0034/000357 data/0034/000358 data/0034/000359 data/0034/000360 data/0034/000361 data/0034/000362 data/0034/000363 data/0034/000364 data/0034/000365 data/0034/000366 data/0034/000367 data/0034/000368 data/0034/000369 data/0034/000370 data/0034/000371 data/0034/000372 data/0034/000373 data/0034/000374 data/0034/000375 data/0034/000376 data/0034/000377 data/0034/000378 data/0034/000379 data/0034/000380 data/0034/000381 data/0034/000382 data/0034/000383 data/0034/000384 data/0034/000385 data/0034/000386 data/0034/000387 data/0034/000388 data/0034/000389 data/0034/000390 data/0034/000391 data/0034/000392 data/0034/000393 data/0034/000394 data/0034/000395 data/0034/000396 data/0034/000397 data/0034/000398 data/0034/000399 data/0034/000400 data/0034/000401 data/0034/000402 data/0034/000403 data/0034/000404 data/0034/000405 data/0034/000406 data/0034/000407 data/0034/000408 data/0034/000409 data/0034/000410 data/0034/000411 data/0034/000412 data/0034/000413 data/0034/000414 data/0034/000415 data/0034/000416 data/0034/000417 data/0034/000418 data/0034/000419 data/0034/000420 data/0034/000421 data/0034/000422 data/0034/000423 data/0034/000424 data/0034/000425 data/0034/000426 data/0034/000427 data/0034/000428 data/0034/000429 data/0034/000430 data/0034/000431 data/0034/000432 data/0034/000433 data/0034/000434 data/0034/000435 data/0034/000436 data/0034/000437 data/0034/000438 data/0034/000439 data/0034/000440 data/0034/000441 data/0034/000442 data/0034/000443 data/0034/000444 data/0034/000445 data/0034/000446 data/0034/000447 data/0034/000448 data/0034/000449 data/0034/000450 data/0034/000451 data/0034/000452 data/0034/000453 data/0034/000454 data/0034/000455 data/0034/000456 data/0034/000457 data/0034/000458 data/0034/000459 data/0034/000460 data/0034/000461 data/0034/000462 data/0034/000463 data/0034/000464 data/0034/000465 data/0034/000466 data/0034/000467 data/0034/000468 data/0034/000469 data/0034/000470 data/0034/000471 data/0034/000472 data/0034/000473 data/0034/000474 data/0034/000475 data/0034/000476 data/0034/000477 data/0034/000478 data/0034/000479 data/0034/000480 data/0034/000481 data/0034/000482 data/0034/000483 data/0034/000484 data/0034/000485 data/0034/000486 data/0034/000487 data/0034/000488 data/0034/000489 data/0034/000490 data/0034/000491 data/0034/000492 data/0034/000493 data/0034/000494 data/0034/000495 data/0034/000496 data/0034/000497 data/0034/000498 data/0034/000499 data/0034/000500 data/0034/000501 data/0034/000502 data/0034/000503 data/0034/000504 data/0034/000505 data/0034/000506 data/0034/000507 data/0034/000508 data/0034/000509 data/0034/000510 data/0034/000511 data/0034/000512 data/0034/000513 data/0034/000514 data/0034/000515 data/0034/000516 data/0034/000517 data/0034/000518 data/0034/000519 data/0034/000520 data/0034/000521 data/0034/000522 data/0034/000523 data/0034/000524 data/0034/000525 data/0034/000526 data/0034/000527 data/0034/000528 data/0034/000529 data/0034/000530 data/0034/000531 data/0034/000532 data/0034/000533 data/0034/000534 data/0034/000535 data/0034/000536 data/0034/000537 data/0034/000538 data/0034/000539 data/0034/000540 data/0034/000541 data/0034/000542 data/0034/000543 data/0034/000544 data/0034/000545 data/0034/000546 data/0034/000547 data/0034/000548 data/0034/000549 data/0034/000550 data/0034/000551 data/0034/000552 data/0034/000553 data/0034/000554 data/0034/000555 data/0034/000556 data/0034/000557 data/0034/000558 data/0034/000559 data/0034/000560 data/0034/000561 data/0034/000562 data/0034/000563 data/0034/000564 data/0034/000565 data/0034/000566 data/0034/000567 data/0034/000568 data/0034/000569 data/0034/000570 data/0034/000571 data/0034/000572 data/0034/000573 data/0034/000574 data/0034/000575 data/0034/000576 data/0034/000577 data/0034/000578 data/0034/000579 data/0034/000580 data/0034/000581 data/0034/000582 data/0034/000583 data/0034/000584 data/0034/000585 data/0034/000586 data/0034/000587 data/0034/000588 data/0034/000589 data/0034/000590 data/0034/000591 data/0034/000592 data/0034/000593 data/0034/000594 data/0034/000595 data/0034/000596 data/0034/000597 data/0034/000598 data/0034/000599 data/0034/000600 data/0034/000601 data/0034/000602 data/0034/000603 data/0034/000604 data/0034/000605 data/0034/000606 data/0034/000607 data/0034/000608 data/0034/000609 data/0034/000610 data/0034/000611 data/0034/000612 data/0034/000613 data/0034/000614 data/0034/000615 data/0034/000616 data/0034/000617 data/0034/000618 data/0034/000619 data/0034/000620 data/0034/000621 data/0034/000622 data/0034/000623 data/0034/000624 data/0034/000625 data/0034/000626 data/0034/000627 data/0034/000628 data/0034/000629 data/0034/000630 data/0034/000631 data/0034/000632 data/0034/000633 data/0034/000634 data/0034/000635 data/0034/000636 data/0034/000637 data/0034/000638 data/0034/000639 data/0034/000640 data/0034/000641 data/0034/000642 data/0034/000643 data/0034/000644 data/0034/000645 data/0034/000646 data/0034/000647 data/0034/000648 data/0034/000649 data/0034/000650 data/0034/000651 data/0034/000652 data/0034/000653 data/0034/000654 data/0034/000655 data/0034/000656 data/0034/000657 data/0034/000658 data/0034/000659 data/0034/000660 data/0034/000661 data/0034/000662 data/0034/000663 data/0034/000664 data/0034/000665 data/0034/000666 data/0034/000667 data/0034/000668 data/0034/000669 data/0034/000670 data/0034/000671 data/0034/000672 data/0034/000673 data/0034/000674 data/0034/000675 data/0034/000676 data/0034/000677 data/0034/000678 data/0034/000679 data/0034/000680 data/0034/000681 data/0034/000682 data/0034/000683 data/0034/000684 data/0034/000685 data/0034/000686 data/0034/000687 data/0034/000688 data/0034/000689 data/0034/000690 data/0034/000691 data/0034/000692 data/0034/000693 data/0034/000694 data/0034/000695 data/0034/000696 data/0034/000697 data/0034/000698 data/0034/000699 data/0034/000700 data/0034/000701 data/0034/000702 data/0034/000703 data/0034/000704 data/0034/000705 data/0034/000706 data/0034/000707 data/0034/000708 data/0034/000709 data/0034/000710 data/0034/000711 data/0034/000712 data/0034/000713 data/0034/000714 data/0034/000715 data/0034/000716 data/0034/000717 data/0034/000718 data/0034/000719 data/0034/000720 data/0034/000721 data/0034/000722 data/0034/000723 data/0034/000724 data/0034/000725 data/0034/000726 data/0034/000727 data/0034/000728 data/0034/000729 data/0034/000730 data/0034/000731 data/0034/000732 data/0034/000733 data/0034/000734 data/0034/000735 data/0034/000736 data/0034/000737 data/0034/000738 data/0034/000739 data/0034/000740 data/0034/000741 data/0034/000742 data/0034/000743 data/0034/000744 data/0034/000745 data/0034/000746 data/0034/000747 data/0034/000748 data/0034/000749 data/0034/000750 data/0034/000751 data/0034/000752 data/0034/000753 data/0034/000754 data/0034/000755 data/0034/000756 data/0034/000757 data/0034/000758 data/0034/000759 data/0034/000760 data/0034/000761 data/0034/000762 data/0034/000763 data/0034/000764 data/0034/000765 data/0034/000766 data/0034/000767 data/0034/000768 data/0034/000769 data/0034/000770 data/0034/000771 data/0034/000772 data/0034/000773 data/0034/000774 data/0034/000775 data/0034/000776 data/0034/000777 data/0034/000778 data/0034/000779 data/0034/000780 data/0034/000781 data/0034/000782 data/0034/000783 data/0034/000784 data/0034/000785 data/0034/000786 data/0035/000001 data/0035/000002 data/0035/000003 data/0035/000004 data/0035/000005 data/0035/000006 data/0035/000007 data/0035/000008 data/0035/000009 data/0035/000010 data/0035/000011 data/0035/000012 data/0035/000013 data/0035/000014 data/0035/000015 data/0035/000016 data/0035/000017 data/0035/000018 data/0035/000019 data/0035/000020 data/0035/000021 data/0035/000022 data/0035/000023 data/0035/000024 data/0035/000025 data/0035/000026 data/0035/000027 data/0035/000028 data/0035/000029 data/0035/000030 data/0035/000031 data/0035/000032 data/0035/000033 data/0035/000034 data/0035/000035 data/0035/000036 data/0035/000037 data/0035/000038 data/0035/000039 data/0035/000040 data/0035/000041 data/0035/000042 data/0035/000043 data/0035/000044 data/0035/000045 data/0035/000046 data/0035/000047 data/0035/000048 data/0035/000049 data/0035/000050 data/0035/000051 data/0035/000052 data/0035/000053 data/0035/000054 data/0035/000055 data/0035/000056 data/0035/000057 data/0035/000058 data/0035/000059 data/0035/000060 data/0035/000061 data/0035/000062 data/0035/000063 data/0035/000064 data/0035/000065 data/0035/000066 data/0035/000067 data/0035/000068 data/0035/000069 data/0035/000070 data/0035/000071 data/0035/000072 data/0035/000073 data/0035/000074 data/0035/000075 data/0035/000076 data/0035/000077 data/0035/000078 data/0035/000079 data/0035/000080 data/0035/000081 data/0035/000082 data/0035/000083 data/0035/000084 data/0035/000085 data/0035/000086 data/0035/000087 data/0035/000088 data/0035/000089 data/0035/000090 data/0035/000091 data/0035/000092 data/0035/000093 data/0035/000094 data/0035/000095 data/0035/000096 data/0035/000097 data/0035/000098 data/0035/000099 data/0035/000100 data/0035/000101 data/0035/000102 data/0035/000103 data/0035/000104 data/0035/000105 data/0035/000106 data/0035/000107 data/0035/000108 data/0035/000109 data/0035/000110 data/0035/000111 data/0035/000112 data/0035/000113 data/0035/000114 data/0035/000115 data/0035/000116 data/0035/000117 data/0035/000118 data/0035/000119 data/0035/000120 data/0035/000121 data/0035/000122 data/0035/000123 data/0035/000124 data/0035/000125 data/0035/000126 data/0035/000127 data/0035/000128 data/0035/000129 data/0035/000130 data/0035/000131 data/0035/000132 data/0035/000133 data/0035/000134 data/0035/000135 data/0035/000136 data/0035/000137 data/0035/000138 data/0035/000139 data/0035/000140 data/0035/000141 data/0035/000142 data/0035/000143 data/0035/000144 data/0035/000145 data/0035/000146 data/0035/000147 data/0035/000148 data/0035/000149 data/0035/000150 data/0035/000151 data/0035/000152 data/0035/000153 data/0035/000154 data/0035/000155 data/0035/000156 data/0035/000157 data/0035/000158 data/0035/000159 data/0035/000160 data/0035/000161 data/0035/000162 data/0035/000163 data/0035/000164 data/0035/000165 data/0035/000166 data/0035/000167 data/0035/000168 data/0035/000169 data/0035/000170 data/0035/000171 data/0035/000172 data/0035/000173 data/0035/000174 data/0035/000175 data/0035/000176 data/0035/000177 data/0035/000178 data/0035/000179 data/0035/000180 data/0035/000181 data/0035/000182 data/0035/000183 data/0035/000184 data/0035/000185 data/0035/000186 data/0035/000187 data/0035/000188 data/0035/000189 data/0035/000190 data/0035/000191 data/0035/000192 data/0035/000193 data/0035/000194 data/0035/000195 data/0035/000196 data/0035/000197 data/0035/000198 data/0035/000199 data/0035/000200 data/0035/000201 data/0035/000202 data/0035/000203 data/0035/000204 data/0035/000205 data/0035/000206 data/0035/000207 data/0035/000208 data/0035/000209 data/0035/000210 data/0035/000211 data/0035/000212 data/0035/000213 data/0035/000214 data/0035/000215 data/0035/000216 data/0035/000217 data/0035/000218 data/0035/000219 data/0035/000220 data/0035/000221 data/0035/000222 data/0035/000223 data/0035/000224 data/0035/000225 data/0035/000226 data/0035/000227 data/0035/000228 data/0035/000229 data/0035/000230 data/0035/000231 data/0035/000232 data/0035/000233 data/0035/000234 data/0035/000235 data/0035/000236 data/0035/000237 data/0035/000238 data/0035/000239 data/0035/000240 data/0035/000241 data/0035/000242 data/0035/000243 data/0035/000244 data/0035/000245 data/0035/000246 data/0035/000247 data/0035/000248 data/0035/000249 data/0035/000250 data/0035/000251 data/0035/000252 data/0035/000253 data/0035/000254 data/0035/000255 data/0035/000256 data/0035/000257 data/0035/000258 data/0035/000259 data/0035/000260 data/0035/000261 data/0035/000262 data/0035/000263 data/0035/000264 data/0035/000265 data/0035/000266 data/0035/000267 data/0035/000268 data/0035/000269 data/0035/000270 data/0035/000271 data/0035/000272 data/0035/000273 data/0035/000274 data/0035/000275 data/0035/000276 data/0035/000277 data/0035/000278 data/0035/000279 data/0035/000280 data/0035/000281 data/0035/000282 data/0035/000283 data/0035/000284 data/0035/000285 data/0035/000286 data/0035/000287 data/0035/000288 data/0035/000289 data/0035/000290 data/0035/000291 data/0035/000292 data/0035/000293 data/0035/000294 data/0035/000295 data/0035/000296 data/0035/000297 data/0035/000298 data/0035/000299 data/0035/000300 data/0035/000301 data/0035/000302 data/0035/000303 data/0035/000304 data/0035/000305 data/0035/000306 data/0035/000307 data/0035/000308 data/0035/000309 data/0035/000310 data/0035/000311 data/0035/000312 data/0035/000313 data/0035/000314 data/0035/000315 data/0035/000316 data/0035/000317 data/0035/000318 data/0035/000319 data/0035/000320 data/0035/000321 data/0035/000322 data/0035/000323 data/0035/000324 data/0035/000325 data/0035/000326 data/0035/000327 data/0035/000328 data/0035/000329 data/0035/000330 data/0035/000331 data/0035/000332 data/0035/000333 data/0035/000334 data/0035/000335 data/0035/000336 data/0035/000337 data/0035/000338 data/0035/000339 data/0035/000340 data/0035/000341 data/0035/000342 data/0035/000343 data/0035/000344 data/0035/000345 data/0035/000346 data/0035/000347 data/0035/000348 data/0035/000349 data/0035/000350 data/0035/000351 data/0035/000352 data/0035/000353 data/0035/000354 data/0035/000355 data/0035/000356 data/0035/000357 data/0035/000358 data/0035/000359 data/0035/000360 data/0035/000361 data/0035/000362 data/0035/000363 data/0035/000364 data/0035/000365 data/0035/000366 data/0035/000367 data/0035/000368 data/0035/000369 data/0035/000370 data/0035/000371 data/0035/000372 data/0035/000373 data/0035/000374 data/0035/000375 data/0035/000376 data/0035/000377 data/0035/000378 data/0035/000379 data/0035/000380 data/0035/000381 data/0035/000382 data/0035/000383 data/0035/000384 data/0035/000385 data/0035/000386 data/0035/000387 data/0035/000388 data/0035/000389 data/0035/000390 data/0035/000391 data/0035/000392 data/0035/000393 data/0035/000394 data/0035/000395 data/0035/000396 data/0035/000397 data/0035/000398 data/0035/000399 data/0035/000400 data/0035/000401 data/0035/000402 data/0035/000403 data/0035/000404 data/0035/000405 data/0035/000406 data/0035/000407 data/0035/000408 data/0035/000409 data/0035/000410 data/0035/000411 data/0035/000412 data/0035/000413 data/0035/000414 data/0035/000415 data/0035/000416 data/0035/000417 data/0035/000418 data/0035/000419 data/0035/000420 data/0035/000421 data/0035/000422 data/0035/000423 data/0035/000424 data/0035/000425 data/0035/000426 data/0035/000427 data/0035/000428 data/0035/000429 data/0035/000430 data/0035/000431 data/0035/000432 data/0035/000433 data/0035/000434 data/0035/000435 data/0035/000436 data/0035/000437 data/0035/000438 data/0035/000439 data/0035/000440 data/0035/000441 data/0035/000442 data/0035/000443 data/0035/000444 data/0035/000445 data/0035/000446 data/0035/000447 data/0035/000448 data/0035/000449 data/0035/000450 data/0035/000451 data/0035/000452 data/0035/000453 data/0035/000454 data/0035/000455 data/0035/000456 data/0035/000457 data/0035/000458 data/0035/000459 data/0035/000460 data/0035/000461 data/0035/000462 data/0035/000463 data/0035/000464 data/0035/000465 data/0035/000466 data/0035/000467 data/0035/000468 data/0035/000469 data/0035/000470 data/0035/000471 data/0035/000472 data/0035/000473 data/0035/000474 data/0035/000475 data/0035/000476 data/0035/000477 data/0035/000478 data/0035/000479 data/0035/000480 data/0035/000481 data/0035/000482 data/0035/000483 data/0035/000484 data/0035/000485 data/0035/000486 data/0035/000487 data/0035/000488 data/0035/000489 data/0035/000490 data/0035/000491 data/0035/000492 data/0035/000493 data/0035/000494 data/0035/000495 data/0035/000496 data/0035/000497 data/0035/000498 data/0035/000499 data/0035/000500 data/0035/000501 data/0035/000502 data/0035/000503 data/0035/000504 data/0035/000505 data/0035/000506 data/0035/000507 data/0035/000508 data/0035/000509 data/0035/000510 data/0035/000511 data/0035/000512 data/0035/000513 data/0035/000514 data/0035/000515 data/0035/000516 data/0035/000517 data/0035/000518 data/0035/000519 data/0035/000520 data/0035/000521 data/0035/000522 data/0035/000523 data/0035/000524 data/0035/000525 data/0035/000526 data/0035/000527 data/0035/000528 data/0035/000529 data/0035/000530 data/0035/000531 data/0035/000532 data/0035/000533 data/0035/000534 data/0035/000535 data/0035/000536 data/0035/000537 data/0035/000538 data/0035/000539 data/0035/000540 data/0035/000541 data/0035/000542 data/0035/000543 data/0035/000544 data/0035/000545 data/0035/000546 data/0035/000547 data/0035/000548 data/0035/000549 data/0035/000550 data/0035/000551 data/0035/000552 data/0035/000553 data/0035/000554 data/0035/000555 data/0035/000556 data/0035/000557 data/0035/000558 data/0035/000559 data/0035/000560 data/0035/000561 data/0035/000562 data/0035/000563 data/0035/000564 data/0035/000565 data/0035/000566 data/0035/000567 data/0035/000568 data/0035/000569 data/0035/000570 data/0035/000571 data/0035/000572 data/0035/000573 data/0035/000574 data/0035/000575 data/0035/000576 data/0035/000577 data/0035/000578 data/0035/000579 data/0035/000580 data/0035/000581 data/0035/000582 data/0035/000583 data/0035/000584 data/0035/000585 data/0035/000586 data/0035/000587 data/0035/000588 data/0035/000589 data/0035/000590 data/0035/000591 data/0035/000592 data/0035/000593 data/0035/000594 data/0035/000595 data/0035/000596 data/0035/000597 data/0035/000598 data/0035/000599 data/0035/000600 data/0035/000601 data/0035/000602 data/0035/000603 data/0035/000604 data/0035/000605 data/0035/000606 data/0035/000607 data/0035/000608 data/0035/000609 data/0035/000610 data/0035/000611 data/0035/000612 data/0035/000613 data/0035/000614 data/0035/000615 data/0035/000616 data/0035/000617 data/0035/000618 data/0035/000619 data/0035/000620 data/0035/000621 data/0035/000622 data/0035/000623 data/0035/000624 data/0035/000625 data/0035/000626 data/0035/000627 data/0035/000628 data/0035/000629 data/0035/000630 data/0035/000631 data/0035/000632 data/0035/000633 data/0035/000634 data/0035/000635 data/0035/000636 data/0035/000637 data/0035/000638 data/0035/000639 data/0035/000640 data/0035/000641 data/0035/000642 data/0035/000643 data/0035/000644 data/0035/000645 data/0035/000646 data/0035/000647 data/0035/000648 data/0035/000649 data/0035/000650 data/0035/000651 data/0035/000652 data/0035/000653 data/0035/000654 data/0035/000655 data/0035/000656 data/0035/000657 data/0035/000658 data/0035/000659 data/0035/000660 data/0035/000661 data/0035/000662 data/0035/000663 data/0035/000664 data/0035/000665 data/0035/000666 data/0035/000667 data/0035/000668 data/0035/000669 data/0035/000670 data/0035/000671 data/0035/000672 data/0035/000673 data/0035/000674 data/0035/000675 data/0035/000676 data/0035/000677 data/0035/000678 data/0035/000679 data/0035/000680 data/0035/000681 data/0035/000682 data/0035/000683 data/0035/000684 data/0035/000685 data/0035/000686 data/0035/000687 data/0035/000688 data/0035/000689 data/0035/000690 data/0035/000691 data/0035/000692 data/0035/000693 data/0035/000694 data/0035/000695 data/0035/000696 data/0035/000697 data/0035/000698 data/0035/000699 data/0035/000700 data/0035/000701 data/0035/000702 data/0035/000703 data/0035/000704 data/0035/000705 data/0035/000706 data/0035/000707 data/0035/000708 data/0035/000709 data/0035/000710 data/0035/000711 data/0035/000712 data/0035/000713 data/0035/000714 data/0035/000715 data/0035/000716 data/0035/000717 data/0035/000718 data/0035/000719 data/0035/000720 data/0035/000721 data/0035/000722 data/0035/000723 data/0035/000724 data/0035/000725 data/0035/000726 data/0035/000727 data/0035/000728 data/0035/000729 data/0035/000730 data/0035/000731 data/0035/000732 data/0035/000733 data/0035/000734 data/0035/000735 data/0035/000736 data/0035/000737 data/0035/000738 data/0035/000739 data/0035/000740 data/0035/000741 data/0035/000742 data/0035/000743 data/0035/000744 data/0035/000745 data/0035/000746 data/0035/000747 data/0035/000748 data/0035/000749 data/0035/000750 data/0035/000751 data/0035/000752 data/0035/000753 data/0035/000754 data/0035/000755 data/0035/000756 data/0035/000757 data/0035/000758 data/0035/000759 data/0035/000760 data/0035/000761 data/0035/000762 data/0035/000763 data/0035/000764 data/0035/000765 data/0035/000766 data/0035/000767 data/0035/000768 data/0035/000769 data/0035/000770 data/0035/000771 data/0035/000772 data/0035/000773 data/0035/000774 data/0035/000775 data/0035/000776 data/0035/000777 data/0035/000778 data/0035/000779 data/0035/000780 data/0035/000781 data/0035/000782 data/0035/000783 data/0035/000784 data/0035/000785 data/0035/000786 data/0035/000787 data/0035/000788 data/0035/000789 data/0035/000790 data/0035/000791 data/0035/000792 data/0035/000793 data/0035/000794 data/0035/000795 data/0035/000796 data/0035/000797 data/0035/000798 data/0035/000799 data/0035/000800 data/0035/000801 data/0035/000802 data/0035/000803 data/0035/000804 data/0035/000805 data/0035/000806 data/0035/000807 data/0035/000808 data/0035/000809 data/0035/000810 data/0035/000811 data/0035/000812 data/0035/000813 data/0035/000814 data/0035/000815 data/0035/000816 data/0035/000817 data/0035/000818 data/0035/000819 data/0035/000820 data/0035/000821 data/0035/000822 data/0035/000823 data/0035/000824 data/0035/000825 data/0035/000826 data/0035/000827 data/0035/000828 data/0035/000829 data/0035/000830 data/0035/000831 data/0035/000832 data/0035/000833 data/0035/000834 data/0035/000835 data/0035/000836 data/0035/000837 data/0035/000838 data/0035/000839 data/0035/000840 data/0035/000841 data/0035/000842 data/0035/000843 data/0035/000844 data/0035/000845 data/0035/000846 data/0035/000847 data/0035/000848 data/0035/000849 data/0035/000850 data/0035/000851 data/0035/000852 data/0036/000001 data/0036/000002 data/0036/000003 data/0036/000004 data/0036/000005 data/0036/000006 data/0036/000007 data/0036/000008 data/0036/000009 data/0036/000010 data/0036/000011 data/0036/000012 data/0036/000013 data/0036/000014 data/0036/000015 data/0036/000016 data/0036/000017 data/0036/000018 data/0036/000019 data/0036/000020 data/0036/000021 data/0036/000022 data/0036/000023 data/0036/000024 data/0036/000025 data/0036/000026 data/0036/000027 data/0036/000028 data/0036/000029 data/0036/000030 data/0036/000031 data/0036/000032 data/0036/000033 data/0036/000034 data/0036/000035 data/0036/000036 data/0036/000037 data/0036/000038 data/0036/000039 data/0036/000040 data/0036/000041 data/0036/000042 data/0036/000043 data/0036/000044 data/0036/000045 data/0036/000046 data/0036/000047 data/0036/000048 data/0036/000049 data/0036/000050 data/0036/000051 data/0036/000052 data/0036/000053 data/0036/000054 data/0036/000055 data/0036/000056 data/0036/000057 data/0036/000058 data/0036/000059 data/0036/000060 data/0036/000061 data/0036/000062 data/0036/000063 data/0036/000064 data/0036/000065 data/0036/000066 data/0036/000067 data/0036/000068 data/0036/000069 data/0036/000070 data/0036/000071 data/0036/000072 data/0036/000073 data/0036/000074 data/0036/000075 data/0036/000076 data/0036/000077 data/0036/000078 data/0036/000079 data/0036/000080 data/0036/000081 data/0036/000082 data/0036/000083 data/0036/000084 data/0036/000085 data/0036/000086 data/0036/000087 data/0036/000088 data/0036/000089 data/0036/000090 data/0036/000091 data/0036/000092 data/0036/000093 data/0036/000094 data/0036/000095 data/0036/000096 data/0036/000097 data/0036/000098 data/0036/000099 data/0036/000100 data/0036/000101 data/0036/000102 data/0036/000103 data/0036/000104 data/0036/000105 data/0036/000106 data/0036/000107 data/0036/000108 data/0036/000109 data/0036/000110 data/0036/000111 data/0036/000112 data/0036/000113 data/0036/000114 data/0036/000115 data/0036/000116 data/0036/000117 data/0036/000118 data/0036/000119 data/0036/000120 data/0036/000121 data/0036/000122 data/0036/000123 data/0036/000124 data/0036/000125 data/0036/000126 data/0036/000127 data/0036/000128 data/0036/000129 data/0036/000130 data/0036/000131 data/0036/000132 data/0036/000133 data/0036/000134 data/0036/000135 data/0036/000136 data/0036/000137 data/0036/000138 data/0036/000139 data/0036/000140 data/0036/000141 data/0036/000142 data/0036/000143 data/0036/000144 data/0036/000145 data/0036/000146 data/0036/000147 data/0036/000148 data/0036/000149 data/0036/000150 data/0036/000151 data/0036/000152 data/0036/000153 data/0036/000154 data/0036/000155 data/0036/000156 data/0036/000157 data/0036/000158 data/0036/000159 data/0036/000160 data/0036/000161 data/0036/000162 data/0036/000163 data/0036/000164 data/0036/000165 data/0036/000166 data/0036/000167 data/0036/000168 data/0036/000169 data/0036/000170 data/0036/000171 data/0036/000172 data/0036/000173 data/0036/000174 data/0036/000175 data/0036/000176 data/0036/000177 data/0036/000178 data/0036/000179 data/0036/000180 data/0036/000181 data/0036/000182 data/0036/000183 data/0036/000184 data/0036/000185 data/0036/000186 data/0036/000187 data/0036/000188 data/0036/000189 data/0036/000190 data/0036/000191 data/0036/000192 data/0036/000193 data/0036/000194 data/0036/000195 data/0036/000196 data/0036/000197 data/0036/000198 data/0036/000199 data/0036/000200 data/0036/000201 data/0036/000202 data/0036/000203 data/0036/000204 data/0036/000205 data/0036/000206 data/0036/000207 data/0036/000208 data/0036/000209 data/0036/000210 data/0036/000211 data/0036/000212 data/0036/000213 data/0036/000214 data/0036/000215 data/0036/000216 data/0036/000217 data/0036/000218 data/0036/000219 data/0036/000220 data/0036/000221 data/0036/000222 data/0036/000223 data/0036/000224 data/0036/000225 data/0036/000226 data/0036/000227 data/0036/000228 data/0036/000229 data/0036/000230 data/0036/000231 data/0036/000232 data/0036/000233 data/0036/000234 data/0036/000235 data/0036/000236 data/0036/000237 data/0036/000238 data/0036/000239 data/0036/000240 data/0036/000241 data/0036/000242 data/0036/000243 data/0036/000244 data/0036/000245 data/0036/000246 data/0036/000247 data/0036/000248 data/0036/000249 data/0036/000250 data/0036/000251 data/0036/000252 data/0036/000253 data/0036/000254 data/0036/000255 data/0036/000256 data/0036/000257 data/0036/000258 data/0036/000259 data/0036/000260 data/0036/000261 data/0036/000262 data/0036/000263 data/0036/000264 data/0036/000265 data/0036/000266 data/0036/000267 data/0036/000268 data/0036/000269 data/0036/000270 data/0036/000271 data/0036/000272 data/0036/000273 data/0036/000274 data/0036/000275 data/0036/000276 data/0036/000277 data/0036/000278 data/0036/000279 data/0036/000280 data/0036/000281 data/0036/000282 data/0036/000283 data/0036/000284 data/0036/000285 data/0036/000286 data/0036/000287 data/0036/000288 data/0036/000289 data/0036/000290 data/0036/000291 data/0036/000292 data/0036/000293 data/0036/000294 data/0036/000295 data/0036/000296 data/0036/000297 data/0036/000298 data/0036/000299 data/0036/000300 data/0036/000301 data/0036/000302 data/0036/000303 data/0036/000304 data/0036/000305 data/0036/000306 data/0036/000307 data/0036/000308 data/0036/000309 data/0036/000310 data/0036/000311 data/0036/000312 data/0036/000313 data/0036/000314 data/0036/000315 data/0036/000316 data/0036/000317 data/0036/000318 data/0036/000319 data/0036/000320 data/0036/000321 data/0036/000322 data/0036/000323 data/0036/000324 data/0036/000325 data/0036/000326 data/0036/000327 data/0036/000328 data/0036/000329 data/0036/000330 data/0036/000331 data/0036/000332 data/0036/000333 data/0036/000334 data/0036/000335 data/0036/000336 data/0036/000337 data/0036/000338 data/0036/000339 data/0036/000340 data/0036/000341 data/0036/000342 data/0036/000343 data/0036/000344 data/0036/000345 data/0036/000346 data/0036/000347 data/0036/000348 data/0036/000349 data/0036/000350 data/0036/000351 data/0036/000352 data/0036/000353 data/0036/000354 data/0036/000355 data/0036/000356 data/0036/000357 data/0036/000358 data/0036/000359 data/0036/000360 data/0036/000361 data/0036/000362 data/0036/000363 data/0036/000364 data/0036/000365 data/0036/000366 data/0036/000367 data/0036/000368 data/0036/000369 data/0036/000370 data/0036/000371 data/0036/000372 data/0036/000373 data/0036/000374 data/0036/000375 data/0036/000376 data/0036/000377 data/0036/000378 data/0036/000379 data/0036/000380 data/0036/000381 data/0036/000382 data/0036/000383 data/0036/000384 data/0036/000385 data/0036/000386 data/0036/000387 data/0036/000388 data/0036/000389 data/0036/000390 data/0036/000391 data/0036/000392 data/0036/000393 data/0036/000394 data/0036/000395 data/0036/000396 data/0036/000397 data/0036/000398 data/0036/000399 data/0036/000400 data/0036/000401 data/0036/000402 data/0036/000403 data/0036/000404 data/0036/000405 data/0036/000406 data/0036/000407 data/0036/000408 data/0036/000409 data/0036/000410 data/0036/000411 data/0036/000412 data/0036/000413 data/0036/000414 data/0036/000415 data/0036/000416 data/0036/000417 data/0036/000418 data/0036/000419 data/0036/000420 data/0036/000421 data/0036/000422 data/0036/000423 data/0036/000424 data/0036/000425 data/0036/000426 data/0036/000427 data/0036/000428 data/0036/000429 data/0036/000430 data/0036/000431 data/0036/000432 data/0036/000433 data/0036/000434 data/0036/000435 data/0036/000436 data/0036/000437 data/0036/000438 data/0036/000439 data/0036/000440 data/0036/000441 data/0036/000442 data/0036/000443 data/0036/000444 data/0036/000445 data/0036/000446 data/0036/000447 data/0036/000448 data/0036/000449 data/0036/000450 data/0036/000451 data/0036/000452 data/0036/000453 data/0036/000454 data/0036/000455 data/0036/000456 data/0036/000457 data/0036/000458 data/0036/000459 data/0036/000460 data/0036/000461 data/0036/000462 data/0036/000463 data/0036/000464 data/0036/000465 data/0036/000466 data/0036/000467 data/0036/000468 data/0036/000469 data/0036/000470 data/0036/000471 data/0036/000472 data/0036/000473 data/0036/000474 data/0036/000475 data/0036/000476 data/0036/000477 data/0036/000478 data/0036/000479 data/0036/000480 data/0036/000481 data/0036/000482 data/0036/000483 data/0036/000484 data/0036/000485 data/0036/000486 data/0036/000487 data/0036/000488 data/0036/000489 data/0036/000490 data/0036/000491 data/0036/000492 data/0036/000493 data/0036/000494 data/0036/000495 data/0036/000496 data/0036/000497 data/0036/000498 data/0036/000499 data/0036/000500 data/0036/000501 data/0036/000502 data/0036/000503 data/0036/000504 data/0036/000505 data/0036/000506 data/0036/000507 data/0036/000508 data/0036/000509 data/0036/000510 data/0036/000511 data/0036/000512 data/0036/000513 data/0036/000514 data/0036/000515 data/0036/000516 data/0036/000517 data/0036/000518 data/0036/000519 data/0036/000520 data/0036/000521 data/0036/000522 data/0036/000523 data/0036/000524 data/0036/000525 data/0036/000526 data/0036/000527 data/0036/000528 data/0036/000529 data/0036/000530 data/0036/000531 data/0036/000532 data/0036/000533 data/0036/000534 data/0036/000535 data/0036/000536 data/0036/000537 data/0036/000538 data/0036/000539 data/0036/000540 data/0036/000541 data/0036/000542 data/0036/000543 data/0036/000544 data/0036/000545 data/0036/000546 data/0036/000547 data/0036/000548 data/0036/000549 data/0036/000550 data/0036/000551 data/0036/000552 data/0036/000553 data/0036/000554 data/0036/000555 data/0036/000556 data/0036/000557 data/0036/000558 data/0036/000559 data/0036/000560 data/0036/000561 data/0036/000562 data/0036/000563 data/0036/000564 data/0036/000565 data/0036/000566 data/0036/000567 data/0036/000568 data/0036/000569 data/0036/000570 data/0036/000571 data/0036/000572 data/0036/000573 data/0036/000574 data/0036/000575 data/0036/000576 data/0036/000577 data/0036/000578 data/0036/000579 data/0036/000580 data/0036/000581 data/0036/000582 data/0036/000583 data/0036/000584 data/0036/000585 data/0036/000586 data/0036/000587 data/0036/000588 data/0036/000589 data/0036/000590 data/0036/000591 data/0036/000592 data/0036/000593 data/0036/000594 data/0036/000595 data/0036/000596 data/0036/000597 data/0036/000598 data/0036/000599 data/0036/000600 data/0036/000601 data/0036/000602 data/0036/000603 data/0036/000604 data/0036/000605 data/0036/000606 data/0036/000607 data/0036/000608 data/0036/000609 data/0036/000610 data/0036/000611 data/0036/000612 data/0036/000613 data/0036/000614 data/0036/000615 data/0036/000616 data/0036/000617 data/0036/000618 data/0036/000619 data/0036/000620 data/0036/000621 data/0036/000622 data/0036/000623 data/0036/000624 data/0036/000625 data/0036/000626 data/0036/000627 data/0036/000628 data/0036/000629 data/0036/000630 data/0036/000631 data/0036/000632 data/0036/000633 data/0036/000634 data/0036/000635 data/0036/000636 data/0036/000637 data/0036/000638 data/0036/000639 data/0036/000640 data/0036/000641 data/0036/000642 data/0036/000643 data/0036/000644 data/0036/000645 data/0036/000646 data/0036/000647 data/0036/000648 data/0036/000649 data/0036/000650 data/0036/000651 data/0036/000652 data/0036/000653 data/0036/000654 data/0036/000655 data/0036/000656 data/0036/000657 data/0036/000658 data/0036/000659 data/0036/000660 data/0036/000661 data/0036/000662 data/0036/000663 data/0036/000664 data/0036/000665 data/0036/000666 data/0036/000667 data/0036/000668 data/0036/000669 data/0036/000670 data/0036/000671 data/0036/000672 data/0036/000673 data/0036/000674 data/0036/000675 data/0036/000676 data/0036/000677 data/0036/000678 data/0036/000679 data/0036/000680 data/0036/000681 data/0036/000682 data/0036/000683 data/0036/000684 data/0036/000685 data/0036/000686 data/0036/000687 data/0036/000688 data/0036/000689 data/0036/000690 data/0036/000691 data/0036/000692 data/0036/000693 data/0036/000694 data/0036/000695 data/0036/000696 data/0036/000697 data/0036/000698 data/0036/000699 data/0036/000700 data/0036/000701 data/0036/000702 data/0036/000703 data/0036/000704 data/0036/000705 data/0036/000706 data/0036/000707 data/0036/000708 data/0036/000709 data/0036/000710 data/0036/000711 data/0036/000712 data/0036/000713 data/0036/000714 data/0036/000715 data/0036/000716 data/0036/000717 data/0036/000718 data/0036/000719 data/0036/000720 data/0036/000721 data/0036/000722 data/0036/000723 data/0036/000724 data/0036/000725 data/0036/000726 data/0036/000727 data/0036/000728 data/0036/000729 data/0036/000730 data/0036/000731 data/0036/000732 data/0036/000733 data/0036/000734 data/0036/000735 data/0036/000736 data/0036/000737 data/0036/000738 data/0036/000739 data/0036/000740 data/0036/000741 data/0036/000742 data/0036/000743 data/0036/000744 data/0036/000745 data/0036/000746 data/0036/000747 data/0036/000748 data/0036/000749 data/0036/000750 data/0036/000751 data/0036/000752 data/0036/000753 data/0036/000754 data/0036/000755 data/0036/000756 data/0036/000757 data/0036/000758 data/0036/000759 data/0036/000760 data/0036/000761 data/0036/000762 data/0036/000763 data/0036/000764 data/0036/000765 data/0036/000766 data/0036/000767 data/0036/000768 data/0036/000769 data/0036/000770 data/0036/000771 data/0036/000772 data/0036/000773 data/0036/000774 data/0036/000775 data/0036/000776 data/0036/000777 data/0036/000778 data/0036/000779 data/0036/000780 data/0036/000781 data/0036/000782 data/0036/000783 data/0036/000784 data/0036/000785 data/0036/000786 data/0036/000787 data/0036/000788 data/0036/000789 data/0036/000790 data/0036/000791 data/0036/000792 data/0036/000793 data/0036/000794 data/0036/000795 data/0036/000796 data/0036/000797 data/0036/000798 data/0036/000799 data/0036/000800 data/0036/000801 data/0036/000802 data/0036/000803 data/0036/000804 data/0036/000805 data/0036/000806 data/0036/000807 data/0036/000808 data/0036/000809 data/0036/000810 data/0036/000811 data/0036/000812 data/0036/000813 data/0036/000814 data/0036/000815 data/0036/000816 data/0036/000817 data/0036/000818 data/0036/000819 data/0036/000820 data/0036/000821 data/0036/000822 data/0036/000823 data/0036/000824 data/0036/000825 data/0037/000001 data/0037/000002 data/0037/000003 data/0037/000004 data/0037/000005 data/0037/000006 data/0037/000007 data/0037/000008 data/0037/000009 data/0037/000010 data/0037/000011 data/0037/000012 data/0037/000013 data/0037/000014 data/0037/000015 data/0037/000016 data/0037/000017 data/0037/000018 data/0037/000019 data/0037/000020 data/0037/000021 data/0037/000022 data/0037/000023 data/0037/000024 data/0037/000025 data/0037/000026 data/0037/000027 data/0037/000028 data/0037/000029 data/0037/000030 data/0037/000031 data/0037/000032 data/0037/000033 data/0037/000034 data/0037/000035 data/0037/000036 data/0037/000037 data/0037/000038 data/0037/000039 data/0037/000040 data/0037/000041 data/0037/000042 data/0037/000043 data/0037/000044 data/0037/000045 data/0037/000046 data/0037/000047 data/0037/000048 data/0037/000049 data/0037/000050 data/0037/000051 data/0037/000052 data/0037/000053 data/0037/000054 data/0037/000055 data/0037/000056 data/0037/000057 data/0037/000058 data/0037/000059 data/0037/000060 data/0037/000061 data/0037/000062 data/0037/000063 data/0037/000064 data/0037/000065 data/0037/000066 data/0037/000067 data/0037/000068 data/0037/000069 data/0037/000070 data/0037/000071 data/0037/000072 data/0037/000073 data/0037/000074 data/0037/000075 data/0037/000076 data/0037/000077 data/0037/000078 data/0037/000079 data/0037/000080 data/0037/000081 data/0037/000082 data/0037/000083 data/0037/000084 data/0037/000085 data/0037/000086 data/0037/000087 data/0037/000088 data/0037/000089 data/0037/000090 data/0037/000091 data/0037/000092 data/0037/000093 data/0037/000094 data/0037/000095 data/0037/000096 data/0037/000097 data/0037/000098 data/0037/000099 data/0037/000100 data/0037/000101 data/0037/000102 data/0037/000103 data/0037/000104 data/0037/000105 data/0037/000106 data/0037/000107 data/0037/000108 data/0037/000109 data/0037/000110 data/0037/000111 data/0037/000112 data/0037/000113 data/0037/000114 data/0037/000115 data/0037/000116 data/0037/000117 data/0037/000118 data/0037/000119 data/0037/000120 data/0037/000121 data/0037/000122 data/0037/000123 data/0037/000124 data/0037/000125 data/0037/000126 data/0037/000127 data/0037/000128 data/0037/000129 data/0037/000130 data/0037/000131 data/0037/000132 data/0037/000133 data/0037/000134 data/0037/000135 data/0037/000136 data/0037/000137 data/0037/000138 data/0037/000139 data/0037/000140 data/0037/000141 data/0037/000142 data/0037/000143 data/0037/000144 data/0037/000145 data/0037/000146 data/0037/000147 data/0037/000148 data/0037/000149 data/0037/000150 data/0037/000151 data/0037/000152 data/0037/000153 data/0037/000154 data/0037/000155 data/0037/000156 data/0037/000157 data/0037/000158 data/0037/000159 data/0037/000160 data/0037/000161 data/0037/000162 data/0037/000163 data/0037/000164 data/0037/000165 data/0037/000166 data/0037/000167 data/0037/000168 data/0037/000169 data/0037/000170 data/0037/000171 data/0037/000172 data/0037/000173 data/0037/000174 data/0037/000175 data/0037/000176 data/0037/000177 data/0037/000178 data/0037/000179 data/0037/000180 data/0037/000181 data/0037/000182 data/0037/000183 data/0037/000184 data/0037/000185 data/0037/000186 data/0037/000187 data/0037/000188 data/0037/000189 data/0037/000190 data/0037/000191 data/0037/000192 data/0037/000193 data/0037/000194 data/0037/000195 data/0037/000196 data/0037/000197 data/0037/000198 data/0037/000199 data/0037/000200 data/0037/000201 data/0037/000202 data/0037/000203 data/0037/000204 data/0037/000205 data/0037/000206 data/0037/000207 data/0037/000208 data/0037/000209 data/0037/000210 data/0037/000211 data/0037/000212 data/0037/000213 data/0037/000214 data/0037/000215 data/0037/000216 data/0037/000217 data/0037/000218 data/0037/000219 data/0037/000220 data/0037/000221 data/0037/000222 data/0037/000223 data/0037/000224 data/0037/000225 data/0037/000226 data/0037/000227 data/0037/000228 data/0037/000229 data/0037/000230 data/0037/000231 data/0037/000232 data/0037/000233 data/0037/000234 data/0037/000235 data/0037/000236 data/0037/000237 data/0037/000238 data/0037/000239 data/0037/000240 data/0037/000241 data/0037/000242 data/0037/000243 data/0037/000244 data/0037/000245 data/0037/000246 data/0037/000247 data/0037/000248 data/0037/000249 data/0037/000250 data/0037/000251 data/0037/000252 data/0037/000253 data/0037/000254 data/0037/000255 data/0037/000256 data/0037/000257 data/0037/000258 data/0037/000259 data/0037/000260 data/0037/000261 data/0037/000262 data/0037/000263 data/0037/000264 data/0037/000265 data/0037/000266 data/0037/000267 data/0037/000268 data/0037/000269 data/0037/000270 data/0037/000271 data/0037/000272 data/0037/000273 data/0037/000274 data/0037/000275 data/0037/000276 data/0037/000277 data/0037/000278 data/0037/000279 data/0037/000280 data/0037/000281 data/0037/000282 data/0037/000283 data/0037/000284 data/0037/000285 data/0037/000286 data/0037/000287 data/0037/000288 data/0037/000289 data/0037/000290 data/0037/000291 data/0037/000292 data/0037/000293 data/0037/000294 data/0037/000295 data/0037/000296 data/0037/000297 data/0037/000298 data/0037/000299 data/0037/000300 data/0037/000301 data/0037/000302 data/0037/000303 data/0037/000304 data/0037/000305 data/0037/000306 data/0037/000307 data/0037/000308 data/0037/000309 data/0037/000310 data/0037/000311 data/0037/000312 data/0037/000313 data/0037/000314 data/0037/000315 data/0037/000316 data/0037/000317 data/0037/000318 data/0037/000319 data/0037/000320 data/0037/000321 data/0037/000322 data/0037/000323 data/0037/000324 data/0037/000325 data/0037/000326 data/0037/000327 data/0037/000328 data/0037/000329 data/0037/000330 data/0037/000331 data/0037/000332 data/0037/000333 data/0037/000334 data/0037/000335 data/0037/000336 data/0037/000337 data/0037/000338 data/0037/000339 data/0037/000340 data/0037/000341 data/0037/000342 data/0037/000343 data/0037/000344 data/0037/000345 data/0037/000346 data/0037/000347 data/0037/000348 data/0037/000349 data/0037/000350 data/0037/000351 data/0037/000352 data/0037/000353 data/0037/000354 data/0037/000355 data/0037/000356 data/0037/000357 data/0037/000358 data/0037/000359 data/0037/000360 data/0037/000361 data/0037/000362 data/0037/000363 data/0037/000364 data/0037/000365 data/0037/000366 data/0037/000367 data/0037/000368 data/0037/000369 data/0037/000370 data/0037/000371 data/0037/000372 data/0037/000373 data/0037/000374 data/0037/000375 data/0037/000376 data/0037/000377 data/0037/000378 data/0037/000379 data/0037/000380 data/0037/000381 data/0037/000382 data/0037/000383 data/0037/000384 data/0037/000385 data/0037/000386 data/0037/000387 data/0037/000388 data/0037/000389 data/0037/000390 data/0037/000391 data/0037/000392 data/0037/000393 data/0037/000394 data/0037/000395 data/0037/000396 data/0037/000397 data/0037/000398 data/0037/000399 data/0037/000400 data/0037/000401 data/0037/000402 data/0037/000403 data/0037/000404 data/0037/000405 data/0037/000406 data/0037/000407 data/0037/000408 data/0037/000409 data/0037/000410 data/0037/000411 data/0037/000412 data/0037/000413 data/0037/000414 data/0037/000415 data/0037/000416 data/0037/000417 data/0037/000418 data/0037/000419 data/0037/000420 data/0037/000421 data/0037/000422 data/0037/000423 data/0037/000424 data/0037/000425 data/0037/000426 data/0037/000427 data/0037/000428 data/0037/000429 data/0037/000430 data/0037/000431 data/0037/000432 data/0037/000433 data/0037/000434 data/0037/000435 data/0037/000436 data/0037/000437 data/0037/000438 data/0037/000439 data/0037/000440 data/0037/000441 data/0037/000442 data/0037/000443 data/0037/000444 data/0037/000445 data/0037/000446 data/0037/000447 data/0037/000448 data/0037/000449 data/0037/000450 data/0037/000451 data/0037/000452 data/0037/000453 data/0037/000454 data/0037/000455 data/0037/000456 data/0037/000457 data/0037/000458 data/0037/000459 data/0037/000460 data/0037/000461 data/0037/000462 data/0037/000463 data/0037/000464 data/0037/000465 data/0037/000466 data/0037/000467 data/0037/000468 data/0037/000469 data/0037/000470 data/0037/000471 data/0037/000472 data/0037/000473 data/0037/000474 data/0037/000475 data/0037/000476 data/0037/000477 data/0037/000478 data/0037/000479 data/0037/000480 data/0037/000481 data/0037/000482 data/0037/000483 data/0037/000484 data/0037/000485 data/0037/000486 data/0037/000487 data/0037/000488 data/0037/000489 data/0037/000490 data/0037/000491 data/0037/000492 data/0037/000493 data/0037/000494 data/0037/000495 data/0037/000496 data/0037/000497 data/0037/000498 data/0037/000499 data/0037/000500 data/0037/000501 data/0037/000502 data/0037/000503 data/0037/000504 data/0037/000505 data/0037/000506 data/0037/000507 data/0037/000508 data/0037/000509 data/0037/000510 data/0037/000511 data/0037/000512 data/0037/000513 data/0037/000514 data/0037/000515 data/0037/000516 data/0037/000517 data/0037/000518 data/0037/000519 data/0037/000520 data/0037/000521 data/0037/000522 data/0037/000523 data/0037/000524 data/0037/000525 data/0037/000526 data/0037/000527 data/0037/000528 data/0037/000529 data/0037/000530 data/0037/000531 data/0037/000532 data/0037/000533 data/0037/000534 data/0037/000535 data/0037/000536 data/0037/000537 data/0037/000538 data/0037/000539 data/0037/000540 data/0037/000541 data/0037/000542 data/0037/000543 data/0037/000544 data/0037/000545 data/0037/000546 data/0037/000547 data/0037/000548 data/0037/000549 data/0037/000550 data/0037/000551 data/0037/000552 data/0037/000553 data/0037/000554 data/0037/000555 data/0037/000556 data/0037/000557 data/0037/000558 data/0037/000559 data/0037/000560 data/0037/000561 data/0037/000562 data/0037/000563 data/0037/000564 data/0037/000565 data/0037/000566 data/0037/000567 data/0037/000568 data/0037/000569 data/0037/000570 data/0037/000571 data/0037/000572 data/0037/000573 data/0037/000574 data/0037/000575 data/0037/000576 data/0037/000577 data/0037/000578 data/0037/000579 data/0037/000580 data/0037/000581 data/0037/000582 data/0037/000583 data/0037/000584 data/0037/000585 data/0037/000586 data/0037/000587 data/0037/000588 data/0037/000589 data/0037/000590 data/0037/000591 data/0037/000592 data/0037/000593 data/0037/000594 data/0037/000595 data/0037/000596 data/0037/000597 data/0037/000598 data/0037/000599 data/0037/000600 data/0037/000601 data/0037/000602 data/0037/000603 data/0037/000604 data/0037/000605 data/0037/000606 data/0037/000607 data/0037/000608 data/0037/000609 data/0037/000610 data/0037/000611 data/0037/000612 data/0037/000613 data/0037/000614 data/0037/000615 data/0037/000616 data/0037/000617 data/0037/000618 data/0037/000619 data/0037/000620 data/0037/000621 data/0037/000622 data/0037/000623 data/0037/000624 data/0037/000625 data/0037/000626 data/0037/000627 data/0037/000628 data/0037/000629 data/0037/000630 data/0037/000631 data/0037/000632 data/0037/000633 data/0037/000634 data/0037/000635 data/0037/000636 data/0037/000637 data/0037/000638 data/0037/000639 data/0037/000640 data/0037/000641 data/0037/000642 data/0037/000643 data/0037/000644 data/0037/000645 data/0037/000646 data/0037/000647 data/0037/000648 data/0037/000649 data/0037/000650 data/0037/000651 data/0037/000652 data/0037/000653 data/0037/000654 data/0037/000655 data/0037/000656 data/0037/000657 data/0037/000658 data/0037/000659 data/0037/000660 data/0037/000661 data/0037/000662 data/0037/000663 data/0037/000664 data/0037/000665 data/0037/000666 data/0037/000667 data/0037/000668 data/0037/000669 data/0037/000670 data/0037/000671 data/0037/000672 data/0037/000673 data/0037/000674 data/0037/000675 data/0037/000676 data/0037/000677 data/0037/000678 data/0037/000679 data/0037/000680 data/0037/000681 data/0037/000682 data/0037/000683 data/0037/000684 data/0037/000685 data/0037/000686 data/0037/000687 data/0037/000688 data/0037/000689 data/0037/000690 data/0037/000691 data/0037/000692 data/0037/000693 data/0037/000694 data/0037/000695 data/0037/000696 data/0037/000697 data/0037/000698 data/0037/000699 data/0037/000700 data/0037/000701 data/0037/000702 data/0037/000703 data/0037/000704 data/0037/000705 data/0037/000706 data/0037/000707 data/0037/000708 data/0037/000709 data/0037/000710 data/0037/000711 data/0037/000712 data/0037/000713 data/0037/000714 data/0037/000715 data/0037/000716 data/0037/000717 data/0037/000718 data/0037/000719 data/0037/000720 data/0037/000721 data/0037/000722 data/0037/000723 data/0037/000724 data/0037/000725 data/0037/000726 data/0037/000727 data/0037/000728 data/0037/000729 data/0037/000730 data/0037/000731 data/0037/000732 data/0037/000733 data/0037/000734 data/0037/000735 data/0037/000736 data/0037/000737 data/0037/000738 data/0037/000739 data/0037/000740 data/0037/000741 data/0037/000742 data/0037/000743 data/0037/000744 data/0037/000745 data/0037/000746 data/0037/000747 data/0037/000748 data/0037/000749 data/0037/000750 data/0037/000751 data/0037/000752 data/0037/000753 data/0037/000754 data/0037/000755 data/0037/000756 data/0037/000757 data/0037/000758 data/0037/000759 data/0037/000760 data/0037/000761 data/0037/000762 data/0037/000763 data/0037/000764 data/0037/000765 data/0037/000766 data/0037/000767 data/0037/000768 data/0037/000769 data/0037/000770 data/0037/000771 data/0037/000772 data/0037/000773 data/0037/000774 data/0037/000775 data/0037/000776 data/0037/000777 data/0037/000778 data/0037/000779 data/0037/000780 data/0037/000781 data/0037/000782 data/0037/000783 data/0037/000784 data/0037/000785 data/0037/000786 data/0037/000787 data/0037/000788 data/0037/000789 data/0037/000790 data/0037/000791 data/0037/000792 data/0037/000793 data/0037/000794 data/0037/000795 data/0037/000796 data/0037/000797 data/0037/000798 data/0037/000799 data/0037/000800 data/0037/000801 data/0037/000802 data/0037/000803 data/0037/000804 data/0037/000805 data/0037/000806 data/0037/000807 data/0037/000808 data/0037/000809 data/0037/000810 data/0037/000811 data/0037/000812 data/0037/000813 data/0037/000814 data/0037/000815 data/0037/000816 data/0037/000817 data/0037/000818 data/0037/000819 data/0037/000820 data/0037/000821 data/0037/000822 data/0037/000823 data/0037/000824 data/0037/000825 data/0037/000826 data/0037/000827 data/0037/000828 data/0037/000829 data/0037/000830 data/0037/000831 data/0037/000832 data/0037/000833 data/0037/000834 data/0037/000835 data/0037/000836 data/0037/000837 data/0037/000838 data/0037/000839 data/0037/000840 data/0037/000841 data/0037/000842 data/0037/000843 data/0037/000844 data/0038/000001 data/0038/000002 data/0038/000003 data/0038/000004 data/0038/000005 data/0038/000006 data/0038/000007 data/0038/000008 data/0038/000009 data/0038/000010 data/0038/000011 data/0038/000012 data/0038/000013 data/0038/000014 data/0038/000015 data/0038/000016 data/0038/000017 data/0038/000018 data/0038/000019 data/0038/000020 data/0038/000021 data/0038/000022 data/0038/000023 data/0038/000024 data/0038/000025 data/0038/000026 data/0038/000027 data/0038/000028 data/0038/000029 data/0038/000030 data/0038/000031 data/0038/000032 data/0038/000033 data/0038/000034 data/0038/000035 data/0038/000036 data/0038/000037 data/0038/000038 data/0038/000039 data/0038/000040 data/0038/000041 data/0038/000042 data/0038/000043 data/0038/000044 data/0038/000045 data/0038/000046 data/0038/000047 data/0038/000048 data/0038/000049 data/0038/000050 data/0038/000051 data/0038/000052 data/0038/000053 data/0038/000054 data/0038/000055 data/0038/000056 data/0038/000057 data/0038/000058 data/0038/000059 data/0038/000060 data/0038/000061 data/0038/000062 data/0038/000063 data/0038/000064 data/0038/000065 data/0038/000066 data/0038/000067 data/0038/000068 data/0038/000069 data/0038/000070 data/0038/000071 data/0038/000072 data/0038/000073 data/0038/000074 data/0038/000075 data/0038/000076 data/0038/000077 data/0038/000078 data/0038/000079 data/0038/000080 data/0038/000081 data/0038/000082 data/0038/000083 data/0038/000084 data/0038/000085 data/0038/000086 data/0038/000087 data/0038/000088 data/0038/000089 data/0038/000090 data/0038/000091 data/0038/000092 data/0038/000093 data/0038/000094 data/0038/000095 data/0038/000096 data/0038/000097 data/0038/000098 data/0038/000099 data/0038/000100 data/0038/000101 data/0038/000102 data/0038/000103 data/0038/000104 data/0038/000105 data/0038/000106 data/0038/000107 data/0038/000108 data/0038/000109 data/0038/000110 data/0038/000111 data/0038/000112 data/0038/000113 data/0038/000114 data/0038/000115 data/0038/000116 data/0038/000117 data/0038/000118 data/0038/000119 data/0038/000120 data/0038/000121 data/0038/000122 data/0038/000123 data/0038/000124 data/0038/000125 data/0038/000126 data/0038/000127 data/0038/000128 data/0038/000129 data/0038/000130 data/0038/000131 data/0038/000132 data/0038/000133 data/0038/000134 data/0038/000135 data/0038/000136 data/0038/000137 data/0038/000138 data/0038/000139 data/0038/000140 data/0038/000141 data/0038/000142 data/0038/000143 data/0038/000144 data/0038/000145 data/0038/000146 data/0038/000147 data/0038/000148 data/0038/000149 data/0038/000150 data/0038/000151 data/0038/000152 data/0038/000153 data/0038/000154 data/0038/000155 data/0038/000156 data/0038/000157 data/0038/000158 data/0038/000159 data/0038/000160 data/0038/000161 data/0038/000162 data/0038/000163 data/0038/000164 data/0038/000165 data/0038/000166 data/0038/000167 data/0038/000168 data/0038/000169 data/0038/000170 data/0038/000171 data/0038/000172 data/0038/000173 data/0038/000174 data/0038/000175 data/0038/000176 data/0038/000177 data/0038/000178 data/0038/000179 data/0038/000180 data/0038/000181 data/0038/000182 data/0038/000183 data/0038/000184 data/0038/000185 data/0038/000186 data/0038/000187 data/0038/000188 data/0038/000189 data/0038/000190 data/0038/000191 data/0038/000192 data/0038/000193 data/0038/000194 data/0038/000195 data/0038/000196 data/0038/000197 data/0038/000198 data/0038/000199 data/0038/000200 data/0038/000201 data/0038/000202 data/0038/000203 data/0038/000204 data/0038/000205 data/0038/000206 data/0038/000207 data/0038/000208 data/0038/000209 data/0038/000210 data/0038/000211 data/0038/000212 data/0038/000213 data/0038/000214 data/0038/000215 data/0038/000216 data/0038/000217 data/0038/000218 data/0038/000219 data/0038/000220 data/0038/000221 data/0038/000222 data/0038/000223 data/0038/000224 data/0038/000225 data/0038/000226 data/0038/000227 data/0038/000228 data/0038/000229 data/0038/000230 data/0038/000231 data/0038/000232 data/0038/000233 data/0038/000234 data/0038/000235 data/0038/000236 data/0038/000237 data/0038/000238 data/0038/000239 data/0038/000240 data/0038/000241 data/0038/000242 data/0038/000243 data/0038/000244 data/0038/000245 data/0038/000246 data/0038/000247 data/0038/000248 data/0038/000249 data/0038/000250 data/0038/000251 data/0038/000252 data/0038/000253 data/0038/000254 data/0038/000255 data/0038/000256 data/0038/000257 data/0038/000258 data/0038/000259 data/0038/000260 data/0038/000261 data/0038/000262 data/0038/000263 data/0038/000264 data/0038/000265 data/0038/000266 data/0038/000267 data/0038/000268 data/0038/000269 data/0038/000270 data/0038/000271 data/0038/000272 data/0038/000273 data/0038/000274 data/0038/000275 data/0038/000276 data/0038/000277 data/0038/000278 data/0038/000279 data/0038/000280 data/0038/000281 data/0038/000282 data/0038/000283 data/0038/000284 data/0038/000285 data/0038/000286 data/0038/000287 data/0038/000288 data/0038/000289 data/0038/000290 data/0038/000291 data/0038/000292 data/0038/000293 data/0038/000294 data/0038/000295 data/0038/000296 data/0038/000297 data/0038/000298 data/0038/000299 data/0038/000300 data/0038/000301 data/0038/000302 data/0038/000303 data/0038/000304 data/0038/000305 data/0038/000306 data/0038/000307 data/0038/000308 data/0038/000309 data/0038/000310 data/0038/000311 data/0038/000312 data/0038/000313 data/0038/000314 data/0038/000315 data/0038/000316 data/0038/000317 data/0038/000318 data/0038/000319 data/0038/000320 data/0038/000321 data/0038/000322 data/0038/000323 data/0038/000324 data/0038/000325 data/0038/000326 data/0038/000327 data/0038/000328 data/0038/000329 data/0038/000330 data/0038/000331 data/0038/000332 data/0038/000333 data/0038/000334 data/0038/000335 data/0038/000336 data/0038/000337 data/0038/000338 data/0038/000339 data/0038/000340 data/0038/000341 data/0038/000342 data/0038/000343 data/0038/000344 data/0038/000345 data/0038/000346 data/0038/000347 data/0038/000348 data/0038/000349 data/0038/000350 data/0038/000351 data/0038/000352 data/0038/000353 data/0038/000354 data/0038/000355 data/0038/000356 data/0038/000357 data/0038/000358 data/0038/000359 data/0038/000360 data/0038/000361 data/0038/000362 data/0038/000363 data/0038/000364 data/0038/000365 data/0038/000366 data/0038/000367 data/0038/000368 data/0038/000369 data/0038/000370 data/0038/000371 data/0038/000372 data/0038/000373 data/0038/000374 data/0038/000375 data/0038/000376 data/0038/000377 data/0038/000378 data/0038/000379 data/0038/000380 data/0038/000381 data/0038/000382 data/0038/000383 data/0038/000384 data/0038/000385 data/0038/000386 data/0038/000387 data/0038/000388 data/0038/000389 data/0038/000390 data/0038/000391 data/0038/000392 data/0038/000393 data/0038/000394 data/0038/000395 data/0038/000396 data/0038/000397 data/0038/000398 data/0038/000399 data/0038/000400 data/0038/000401 data/0038/000402 data/0038/000403 data/0038/000404 data/0038/000405 data/0038/000406 data/0038/000407 data/0038/000408 data/0038/000409 data/0038/000410 data/0038/000411 data/0038/000412 data/0038/000413 data/0038/000414 data/0038/000415 data/0038/000416 data/0038/000417 data/0038/000418 data/0038/000419 data/0038/000420 data/0038/000421 data/0038/000422 data/0038/000423 data/0038/000424 data/0038/000425 data/0038/000426 data/0038/000427 data/0038/000428 data/0038/000429 data/0038/000430 data/0038/000431 data/0038/000432 data/0038/000433 data/0038/000434 data/0038/000435 data/0038/000436 data/0038/000437 data/0038/000438 data/0038/000439 data/0038/000440 data/0038/000441 data/0038/000442 data/0038/000443 data/0038/000444 data/0038/000445 data/0038/000446 data/0038/000447 data/0038/000448 data/0038/000449 data/0038/000450 data/0038/000451 data/0038/000452 data/0038/000453 data/0038/000454 data/0038/000455 data/0038/000456 data/0038/000457 data/0038/000458 data/0038/000459 data/0038/000460 data/0038/000461 data/0038/000462 data/0038/000463 data/0038/000464 data/0038/000465 data/0038/000466 data/0038/000467 data/0038/000468 data/0038/000469 data/0038/000470 data/0038/000471 data/0038/000472 data/0038/000473 data/0038/000474 data/0038/000475 data/0038/000476 data/0038/000477 data/0038/000478 data/0038/000479 data/0038/000480 data/0038/000481 data/0038/000482 data/0038/000483 data/0038/000484 data/0038/000485 data/0038/000486 data/0038/000487 data/0038/000488 data/0038/000489 data/0038/000490 data/0038/000491 data/0038/000492 data/0038/000493 data/0038/000494 data/0038/000495 data/0038/000496 data/0038/000497 data/0038/000498 data/0038/000499 data/0038/000500 data/0038/000501 data/0038/000502 data/0038/000503 data/0038/000504 data/0038/000505 data/0038/000506 data/0038/000507 data/0038/000508 data/0038/000509 data/0038/000510 data/0038/000511 data/0038/000512 data/0038/000513 data/0038/000514 data/0038/000515 data/0038/000516 data/0038/000517 data/0038/000518 data/0038/000519 data/0038/000520 data/0038/000521 data/0038/000522 data/0038/000523 data/0038/000524 data/0038/000525 data/0038/000526 data/0038/000527 data/0038/000528 data/0038/000529 data/0038/000530 data/0038/000531 data/0038/000532 data/0038/000533 data/0038/000534 data/0038/000535 data/0038/000536 data/0038/000537 data/0038/000538 data/0038/000539 data/0038/000540 data/0038/000541 data/0038/000542 data/0038/000543 data/0038/000544 data/0038/000545 data/0038/000546 data/0038/000547 data/0038/000548 data/0038/000549 data/0038/000550 data/0038/000551 data/0038/000552 data/0038/000553 data/0038/000554 data/0038/000555 data/0038/000556 data/0038/000557 data/0038/000558 data/0038/000559 data/0038/000560 data/0038/000561 data/0038/000562 data/0038/000563 data/0038/000564 data/0038/000565 data/0038/000566 data/0038/000567 data/0038/000568 data/0038/000569 data/0038/000570 data/0038/000571 data/0038/000572 data/0038/000573 data/0038/000574 data/0038/000575 data/0038/000576 data/0038/000577 data/0038/000578 data/0038/000579 data/0038/000580 data/0038/000581 data/0038/000582 data/0038/000583 data/0038/000584 data/0038/000585 data/0038/000586 data/0038/000587 data/0038/000588 data/0038/000589 data/0038/000590 data/0038/000591 data/0038/000592 data/0038/000593 data/0038/000594 data/0038/000595 data/0038/000596 data/0038/000597 data/0038/000598 data/0038/000599 data/0038/000600 data/0038/000601 data/0038/000602 data/0038/000603 data/0038/000604 data/0038/000605 data/0038/000606 data/0038/000607 data/0038/000608 data/0038/000609 data/0038/000610 data/0038/000611 data/0038/000612 data/0038/000613 data/0038/000614 data/0038/000615 data/0038/000616 data/0038/000617 data/0038/000618 data/0038/000619 data/0038/000620 data/0038/000621 data/0038/000622 data/0038/000623 data/0038/000624 data/0038/000625 data/0038/000626 data/0038/000627 data/0038/000628 data/0038/000629 data/0038/000630 data/0038/000631 data/0038/000632 data/0038/000633 data/0038/000634 data/0038/000635 data/0038/000636 data/0038/000637 data/0038/000638 data/0038/000639 data/0038/000640 data/0038/000641 data/0038/000642 data/0038/000643 data/0038/000644 data/0038/000645 data/0038/000646 data/0038/000647 data/0038/000648 data/0038/000649 data/0038/000650 data/0038/000651 data/0038/000652 data/0038/000653 data/0038/000654 data/0038/000655 data/0038/000656 data/0038/000657 data/0038/000658 data/0038/000659 data/0038/000660 data/0038/000661 data/0038/000662 data/0038/000663 data/0038/000664 data/0038/000665 data/0038/000666 data/0038/000667 data/0038/000668 data/0038/000669 data/0038/000670 data/0038/000671 data/0038/000672 data/0038/000673 data/0038/000674 data/0038/000675 data/0038/000676 data/0038/000677 data/0038/000678 data/0038/000679 data/0038/000680 data/0038/000681 data/0038/000682 data/0038/000683 data/0038/000684 data/0038/000685 data/0038/000686 data/0038/000687 data/0038/000688 data/0038/000689 data/0038/000690 data/0038/000691 data/0038/000692 data/0038/000693 data/0038/000694 data/0038/000695 data/0038/000696 data/0038/000697 data/0038/000698 data/0038/000699 data/0038/000700 data/0038/000701 data/0038/000702 data/0038/000703 data/0038/000704 data/0038/000705 data/0038/000706 data/0038/000707 data/0038/000708 data/0038/000709 data/0038/000710 data/0038/000711 data/0038/000712 data/0038/000713 data/0038/000714 data/0038/000715 data/0038/000716 data/0038/000717 data/0038/000718 data/0038/000719 data/0038/000720 data/0038/000721 data/0038/000722 data/0038/000723 data/0038/000724 data/0038/000725 data/0038/000726 data/0038/000727 data/0038/000728 data/0038/000729 data/0038/000730 data/0038/000731 data/0038/000732 data/0038/000733 data/0038/000734 data/0038/000735 data/0038/000736 data/0038/000737 data/0038/000738 data/0038/000739 data/0038/000740 data/0038/000741 data/0038/000742 data/0038/000743 data/0038/000744 data/0038/000745 data/0038/000746 data/0038/000747 data/0038/000748 data/0038/000749 data/0038/000750 data/0038/000751 data/0038/000752 data/0038/000753 data/0038/000754 data/0038/000755 data/0038/000756 data/0038/000757 data/0038/000758 data/0038/000759 data/0038/000760 data/0038/000761 data/0038/000762 data/0038/000763 data/0038/000764 data/0038/000765 data/0038/000766 data/0038/000767 data/0038/000768 data/0038/000769 data/0038/000770 data/0038/000771 data/0038/000772 data/0038/000773 data/0038/000774 data/0038/000775 data/0038/000776 data/0038/000777 data/0038/000778 data/0038/000779 data/0038/000780 data/0038/000781 data/0038/000782 data/0038/000783 data/0038/000784 data/0038/000785 data/0038/000786 data/0038/000787 data/0038/000788 data/0038/000789 data/0038/000790 data/0038/000791 data/0038/000792 data/0038/000793 data/0038/000794 data/0038/000795 data/0038/000796 data/0038/000797 data/0038/000798 data/0038/000799 data/0038/000800 data/0038/000801 data/0038/000802 data/0038/000803 data/0038/000804 data/0038/000805 data/0038/000806 data/0038/000807 data/0038/000808 data/0038/000809 data/0038/000810 data/0038/000811 data/0038/000812 data/0038/000813 data/0038/000814 data/0038/000815 data/0038/000816 data/0038/000817 data/0038/000818 data/0038/000819 data/0038/000820 data/0038/000821 data/0038/000822 data/0038/000823 data/0038/000824 data/0038/000825 data/0038/000826 data/0038/000827 data/0038/000828 data/0038/000829 data/0038/000830 data/0038/000831 data/0038/000832 data/0038/000833 data/0038/000834 data/0038/000835 data/0038/000836 data/0038/000837 data/0038/000838 data/0038/000839 data/0038/000840 data/0038/000841 data/0038/000842 data/0038/000843 data/0038/000844 data/0038/000845 data/0038/000846 data/0038/000847 data/0038/000848 data/0038/000849 data/0038/000850 data/0038/000851 data/0038/000852 data/0038/000853 data/0038/000854 data/0038/000855 data/0038/000856 data/0038/000857 data/0038/000858 data/0038/000859 data/0038/000860 data/0038/000861 data/0038/000862 data/0038/000863 data/0038/000864 data/0038/000865 data/0038/000866 data/0038/000867 data/0038/000868 data/0038/000869 data/0038/000870 data/0038/000871 data/0038/000872 data/0038/000873 data/0038/000874 data/0038/000875 data/0038/000876 data/0038/000877 data/0038/000878 data/0038/000879 data/0038/000880 data/0038/000881 data/0038/000882 data/0038/000883 data/0038/000884 data/0038/000885 data/0038/000886 data/0038/000887 data/0038/000888 data/0038/000889 data/0038/000890 data/0038/000891 data/0038/000892 data/0038/000893 data/0038/000894 data/0038/000895 data/0038/000896 data/0038/000897 data/0038/000898 data/0038/000899 data/0038/000900 data/0038/000901 data/0038/000902 data/0038/000903 data/0038/000904 data/0038/000905 data/0038/000906 data/0038/000907 data/0038/000908 data/0038/000909 data/0038/000910 data/0038/000911 data/0038/000912 data/0038/000913 data/0038/000914 data/0038/000915 data/0038/000916 data/0038/000917 data/0038/000918 data/0038/000919 data/0038/000920 data/0038/000921 data/0038/000922 data/0038/000923 data/0038/000924 data/0038/000925 data/0038/000926 data/0038/000927 data/0038/000928 data/0038/000929 data/0038/000930 data/0038/000931 data/0038/000932 data/0038/000933 data/0038/000934 data/0038/000935 data/0038/000936 data/0038/000937 data/0038/000938 data/0038/000939 data/0038/000940 data/0038/000941 data/0038/000942 data/0038/000943 data/0038/000944 data/0038/000945 data/0038/000946 data/0038/000947 data/0038/000948 data/0038/000949 data/0038/000950 data/0038/000951 data/0038/000952 data/0038/000953 data/0038/000954 data/0038/000955 data/0038/000956 data/0038/000957 data/0038/000958 data/0038/000959 data/0038/000960 data/0038/000961 data/0038/000962 data/0038/000963 data/0038/000964 data/0038/000965 data/0038/000966 data/0038/000967 data/0038/000968 data/0038/000969 data/0038/000970 data/0038/000971 data/0038/000972 data/0038/000973 data/0038/000974 data/0038/000975 data/0038/000976 data/0038/000977 data/0038/000978 data/0038/000979 data/0038/000980 data/0038/000981 data/0038/000982 data/0038/000983 data/0038/000984 data/0038/000985 data/0038/000986 data/0038/000987 data/0038/000988 data/0038/000989 data/0038/000990 data/0038/000991 data/0038/000992 data/0038/000993 data/0038/000994 data/0038/000995 data/0038/000996 data/0038/000997 data/0038/000998 data/0038/000999 data/0038/001000 data/0038/001001 data/0038/001002 data/0038/001003 data/0038/001004 data/0038/001005 data/0038/001006 data/0038/001007 data/0038/001008 data/0038/001009 data/0038/001010 data/0038/001011 data/0038/001012 data/0038/001013 data/0038/001014 data/0038/001015 data/0038/001016 data/0038/001017 data/0038/001018 data/0038/001019 data/0038/001020 data/0038/001021 data/0038/001022 data/0038/001023 data/0038/001024 data/0038/001025 data/0038/001026 data/0038/001027 data/0038/001028 data/0038/001029 data/0038/001030 data/0038/001031 data/0038/001032 data/0038/001033 data/0038/001034 data/0038/001035 data/0038/001036 data/0038/001037 data/0038/001038 data/0038/001039 data/0038/001040 data/0038/001041 data/0038/001042 data/0038/001043 data/0038/001044 data/0038/001045 data/0038/001046 data/0038/001047 data/0038/001048 data/0038/001049 data/0038/001050 data/0038/001051 data/0038/001052 data/0038/001053 data/0038/001054 data/0038/001055 data/0038/001056 data/0038/001057 data/0038/001058 data/0038/001059 data/0038/001060 data/0038/001061 data/0038/001062 data/0038/001063 data/0038/001064 data/0038/001065 data/0038/001066 data/0038/001067 data/0038/001068 data/0038/001069 data/0038/001070 data/0038/001071 data/0038/001072 data/0038/001073 data/0038/001074 data/0038/001075 data/0038/001076 data/0038/001077 data/0038/001078 data/0038/001079 data/0038/001080 data/0038/001081 data/0038/001082 data/0038/001083 data/0038/001084 data/0038/001085 data/0038/001086 data/0038/001087 data/0038/001088 data/0038/001089 data/0038/001090 data/0038/001091 data/0038/001092 data/0038/001093 data/0038/001094 data/0038/001095 data/0038/001096 data/0038/001097 data/0038/001098 data/0038/001099 data/0038/001100 data/0038/001101 data/0038/001102 data/0038/001103 data/0038/001104 data/0038/001105 data/0038/001106 data/0038/001107 data/0038/001108 data/0038/001109 data/0038/001110 data/0038/001111 data/0038/001112 data/0038/001113 data/0038/001114 data/0038/001115 data/0038/001116 data/0038/001117 data/0038/001118 data/0038/001119 data/0038/001120 data/0038/001121 data/0038/001122 data/0038/001123 data/0038/001124 data/0038/001125 data/0038/001126 data/0038/001127 data/0038/001128 data/0038/001129 data/0038/001130 data/0038/001131 data/0038/001132 data/0038/001133 data/0038/001134 data/0038/001135 data/0038/001136 data/0038/001137 data/0038/001138 data/0038/001139 data/0038/001140 data/0038/001141 data/0038/001142 data/0038/001143 data/0038/001144 data/0038/001145 data/0038/001146 data/0038/001147 data/0038/001148 data/0038/001149 data/0038/001150 data/0038/001151 data/0038/001152 data/0038/001153 data/0038/001154 data/0038/001155 data/0038/001156 data/0038/001157 data/0038/001158 data/0038/001159 data/0038/001160 data/0038/001161 data/0038/001162 data/0038/001163 data/0038/001164 data/0038/001165 data/0038/001166 data/0038/001167 data/0038/001168 data/0038/001169 data/0038/001170 data/0038/001171 data/0038/001172 data/0038/001173 data/0038/001174 data/0038/001175 data/0038/001176 data/0038/001177 data/0038/001178 data/0038/001179 data/0038/001180 data/0038/001181 data/0038/001182 data/0038/001183 data/0038/001184 data/0038/001185 data/0038/001186 data/0038/001187 data/0038/001188 data/0038/001189 data/0038/001190 data/0038/001191 data/0038/001192 data/0038/001193 data/0038/001194 ================================================ FILE: DenseFusion/docker/Dockerfile ================================================ FROM nvidia/cuda:10.0-cudnn7-devel-ubuntu16.04 MAINTAINER Dinh-Cuong Hoang # Supress warnings about missing front-end. As recommended at: # http://stackoverflow.com/questions/22466255/is-it-possibe-to-answer-dialog-questions-when-installing-under-docker ARG DEBIAN_FRONTEND=noninteractive # Essentials: developer tools, build tools, OpenBLAS RUN apt-get update && apt-get install -y --no-install-recommends \ apt-utils git curl vim unzip openssh-client wget \ build-essential cmake \ libopenblas-dev # Python 3.5 # For convenience, alias (but don't sym-link) python & pip to python3 & pip3 as recommended in: # http://askubuntu.com/questions/351318/changing-symlink-python-to-python3-causes-problems RUN apt-get install -y --no-install-recommends python3.5 python3.5-dev python3-pip python3-tk && \ pip3 install --no-cache-dir --upgrade pip setuptools && \ echo "alias python='python3'" >> /root/.bash_aliases && \ echo "alias pip='pip3'" >> /root/.bash_aliases # Pillow and it's dependencies RUN apt-get install -y --no-install-recommends libjpeg-dev zlib1g-dev && \ pip3 --no-cache-dir install Pillow # Science libraries and other common packages RUN pip3 --no-cache-dir install \ numpy scipy pyyaml cffi pyyaml matplotlib Cython requests # Jupyter Notebook # Allow access from outside the container, and skip trying to open a browser. # NOTE: disable authentication token for convenience. DON'T DO THIS ON A PUBLIC SERVER. RUN pip3 --no-cache-dir install jupyter && \ mkdir /root/.jupyter && \ echo "c.NotebookApp.ip = '*'" \ "\nc.NotebookApp.open_browser = False" \ "\nc.NotebookApp.token = ''" \ > /root/.jupyter/jupyter_notebook_config.py EXPOSE 8888 # Tensorflow 1.11 - GPU RUN pip3 install https://download.pytorch.org/whl/cu100/torch-1.0.1.post2-cp35-cp35m-linux_x86_64.whl RUN pip3 install torchvision==0.2.2.post3 # Expose port for TensorBoard EXPOSE 6006 ================================================ FILE: DenseFusion/docker/docker_build.sh ================================================ #!/bin/bash # # This script runs docker build to create the maskrcnn-gpu docker image. # set -exu sudo nvidia-docker build --tag densefusion-pytorch-1.0 ./ ================================================ FILE: DenseFusion/docker/docker_run.sh ================================================ #!/bin/bash # # Usage: ./docker_run.sh [/path/to/data] # # This script calls `nvidia-docker run` to start the labelfusion # container with an interactive bash session. This script sets # the required environment variables and mounts the labelfusion # source directory as a volume in the docker container. If the # path to a data directory is given then the data directory is # also mounted as a volume. # image_name=hoangcuongbk80/densefusion-gpu:latest nvidia-docker run --name densefusion -it --rm -v /home/aass/Hoang-Cuong/Seg_SLAM/DenseFusion:/densefusion -v /media/aass/783de628-b7ff-4217-8c96-7f3764de70d9/Warehouse_Dataset:/warehouse_dataset densefusion-gpu /bin/bash nvidia-docker run --name densefusion -it --rm -v /home/cghg/DenseFusion:/densefusion -v /media/DiskStation/trsv/data/YCB_Video_Dataset:/YCB_Video_Dataset hoangcuongbk80/densefusion-pytorch-1.0 /bin/bash ================================================ FILE: DenseFusion/download.sh ================================================ # Download the datasets and checkpoints if [ ! -d datasets/ycb/YCB_Video_Dataset ];then echo 'Downloading the YCB-Video Dataset' wget --load-cookies /tmp/cookies.txt "https://docs.google.com/uc?export=download&confirm=$(wget --quiet --save-cookies /tmp/cookies.txt --keep-session-cookies --no-check-certificate 'https://docs.google.com/uc?export=download&id=1if4VoEXNx9W3XCn0Y7Fp15B4GpcYbyYi' -O- | sed -rn 's/.*confirm=([0-9A-Za-z_]+).*/\1\n/p')&id=1if4VoEXNx9W3XCn0Y7Fp15B4GpcYbyYi" -O YCB_Video_Dataset.zip && rm -rf /tmp/cookies.txt \ && unzip YCB_Video_Dataset.zip \ && mv YCB_Video_Dataset/ datasets/ycb/ \ && rm YCB_Video_Dataset.zip fi if [ ! -d datasets/linemod/Linemod_preprocessed ];then echo 'Downloading the preprocessed LineMOD dataset' wget --load-cookies /tmp/cookies.txt "https://docs.google.com/uc?export=download&confirm=$(wget --quiet --save-cookies /tmp/cookies.txt --keep-session-cookies --no-check-certificate 'https://docs.google.com/uc?export=download&id=1YFUra533pxS_IHsb9tB87lLoxbcHYXt8' -O- | sed -rn 's/.*confirm=([0-9A-Za-z_]+).*/\1\n/p')&id=1YFUra533pxS_IHsb9tB87lLoxbcHYXt8" -O Linemod_preprocessed.zip && rm -rf /tmp/cookies.txt \ && unzip Linemod_preprocessed.zip \ && mv Linemod_preprocessed/ datasets/linemod/ \ && rm Linemod_preprocessed.zip fi if [ ! -d trained_checkpoints ];then echo 'Downloading the trained checkpoints...' wget --load-cookies /tmp/cookies.txt "https://docs.google.com/uc?export=download&confirm=$(wget --quiet --save-cookies /tmp/cookies.txt --keep-session-cookies --no-check-certificate 'https://docs.google.com/uc?export=download&id=1bQ9H-fyZplQoNt1qRwdIUX5_3_1pj6US' -O- | sed -rn 's/.*confirm=([0-9A-Za-z_]+).*/\1\n/p')&id=1bQ9H-fyZplQoNt1qRwdIUX5_3_1pj6US" -O trained_checkpoints.zip && rm -rf /tmp/cookies.txt \ && unzip trained_checkpoints.zip -x "__MACOSX/*" "*.DS_Store" "*.gitignore" -d trained_checkpoints \ && mv trained_checkpoints/trained*/ycb trained_checkpoints/ycb \ && mv trained_checkpoints/trained*/linemod trained_checkpoints/linemod \ && rm -r trained_checkpoints/trained*/ \ && rm trained_checkpoints.zip fi echo 'done' ================================================ FILE: DenseFusion/experiments/logs/warehouse/note ================================================ ================================================ FILE: DenseFusion/experiments/scripts/iliad.sh ================================================ #!/bin/bash set -x set -e export PYTHONUNBUFFERED="True" export CUDA_VISIBLE_DEVICES=0 python3 ./tools/iliad.py --dataset_root /home/aass/catkin_ws/src/Object-RPE/data/dataset/warehouse\ --saved_root /home/aass/catkin_ws/src/Object-RPE/data\ --model trained_checkpoints/warehouse/pose_model_54_0.019968815155302567.pth\ --refine_model trained_checkpoints/warehouse/pose_refine_model_92_0.01590736784950592.pth ================================================ FILE: DenseFusion/experiments/scripts/train_warehouse.sh ================================================ #!/bin/bash set -x set -e export PYTHONUNBUFFERED="True" export CUDA_VISIBLE_DEVICES=0 python3 ./tools/train.py --dataset warehouse\ --dataset_root /warehouse_dataset ================================================ FILE: DenseFusion/lib/extractors.py ================================================ from collections import OrderedDict import math import random import torch import torch.nn as nn import torch.nn.functional as F def load_weights_sequential(target, source_state): new_dict = OrderedDict() for (k1, v1), (k2, v2) in zip(target.state_dict().items(), source_state.items()): new_dict[k1] = v2 target.load_state_dict(new_dict) def conv3x3(in_planes, out_planes, stride=1, dilation=1): return nn.Conv2d(in_planes, out_planes, kernel_size=3, stride=stride, padding=dilation, dilation=dilation, bias=False) class BasicBlock(nn.Module): expansion = 1 def __init__(self, inplanes, planes, stride=1, downsample=None, dilation=1): super(BasicBlock, self).__init__() self.conv1 = conv3x3(inplanes, planes, stride=stride, dilation=dilation) self.relu = nn.ReLU(inplace=True) self.conv2 = conv3x3(planes, planes, stride=1, dilation=dilation) self.downsample = downsample self.stride = stride def forward(self, x): residual = x out = self.conv1(x) out = self.relu(out) out = self.conv2(out) if self.downsample is not None: residual = self.downsample(x) out += residual out = self.relu(out) return out class Bottleneck(nn.Module): expansion = 4 def __init__(self, inplanes, planes, stride=1, downsample=None, dilation=1): super(Bottleneck, self).__init__() self.conv1 = nn.Conv2d(inplanes, planes, kernel_size=1, bias=False) self.conv2 = nn.Conv2d(planes, planes, kernel_size=3, stride=stride, dilation=dilation, padding=dilation, bias=False) self.conv3 = nn.Conv2d(planes, planes * 4, kernel_size=1, bias=False) self.relu = nn.ReLU(inplace=True) self.downsample = downsample self.stride = stride def forward(self, x): residual = x out = self.conv1(x) out = self.relu(out) out = self.conv2(out) out = self.relu(out) out = self.conv3(out) if self.downsample is not None: residual = self.downsample(x) out += residual out = self.relu(out) return out class ResNet(nn.Module): def __init__(self, block, layers=(3, 4, 23, 3)): self.inplanes = 64 super(ResNet, self).__init__() self.conv1 = nn.Conv2d(3, 64, kernel_size=7, stride=2, padding=3, bias=False) self.relu = nn.ReLU(inplace=True) self.maxpool = nn.MaxPool2d(kernel_size=3, stride=2, padding=1) self.layer1 = self._make_layer(block, 64, layers[0]) self.layer2 = self._make_layer(block, 128, layers[1], stride=2) self.layer3 = self._make_layer(block, 256, layers[2], stride=1, dilation=2) self.layer4 = self._make_layer(block, 512, layers[3], stride=1, dilation=4) for m in self.modules(): if isinstance(m, nn.Conv2d): n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels m.weight.data.normal_(0, math.sqrt(2. / n)) elif isinstance(m, nn.BatchNorm2d): m.weight.data.fill_(1) m.bias.data.zero_() def _make_layer(self, block, planes, blocks, stride=1, dilation=1): downsample = None if stride != 1 or self.inplanes != planes * block.expansion: downsample = nn.Sequential( nn.Conv2d(self.inplanes, planes * block.expansion, kernel_size=1, stride=stride, bias=False) ) layers = [block(self.inplanes, planes, stride, downsample)] self.inplanes = planes * block.expansion for i in range(1, blocks): layers.append(block(self.inplanes, planes, dilation=dilation)) return nn.Sequential(*layers) def forward(self, x): x = self.conv1(x) x = self.relu(x) x = self.maxpool(x) x = self.layer1(x) x = self.layer2(x) x_3 = self.layer3(x) x = self.layer4(x_3) return x, x_3 def resnet18(pretrained=False): model = ResNet(BasicBlock, [2, 2, 2, 2]) return model def resnet34(pretrained=False): model = ResNet(BasicBlock, [3, 4, 6, 3]) return model def resnet50(pretrained=False): model = ResNet(Bottleneck, [3, 4, 6, 3]) return model def resnet101(pretrained=False): model = ResNet(Bottleneck, [3, 4, 23, 3]) return model def resnet152(pretrained=False): model = ResNet(Bottleneck, [3, 8, 36, 3]) return model ================================================ FILE: DenseFusion/lib/knn/__init__.py ================================================ import unittest import gc import operator as op import functools import torch from torch.autograd import Variable, Function from lib.knn import knn_pytorch as knn_pytorch class KNearestNeighbor(Function): """ Compute k nearest neighbors for each query point. """ def __init__(self, k): self.k = k def forward(self, ref, query): ref = ref.float().cuda() query = query.float().cuda() inds = torch.empty(query.shape[0], self.k, query.shape[2]).long().cuda() knn_pytorch.knn(ref, query, inds) return inds class TestKNearestNeighbor(unittest.TestCase): def test_forward(self): knn = KNearestNeighbor(2) while(1): D, N, M = 128, 100, 1000 ref = Variable(torch.rand(2, D, N)) query = Variable(torch.rand(2, D, M)) inds = knn(ref, query) for obj in gc.get_objects(): if torch.is_tensor(obj): print(functools.reduce(op.mul, obj.size()) if len(obj.size()) > 0 else 0, type(obj), obj.size()) #ref = ref.cpu() #query = query.cpu() print(inds) if __name__ == '__main__': unittest.main() ================================================ FILE: DenseFusion/lib/knn/knn_pytorch.egg-info/PKG-INFO ================================================ Metadata-Version: 1.0 Name: knn-pytorch Version: 0.1 Summary: KNN implement in Pytorch 1.0 including both cpu version and gpu version Home-page: https://github.com/foolyc/torchKNN Author: foolyc Author-email: UNKNOWN License: UNKNOWN Description: UNKNOWN Platform: UNKNOWN ================================================ FILE: DenseFusion/lib/knn/knn_pytorch.egg-info/SOURCES.txt ================================================ setup.py /densefusion/lib/knn/src/vision.cpp /densefusion/lib/knn/src/cpu/knn_cpu.cpp /densefusion/lib/knn/src/cuda/knn.cu knn_pytorch.egg-info/PKG-INFO knn_pytorch.egg-info/SOURCES.txt knn_pytorch.egg-info/dependency_links.txt knn_pytorch.egg-info/top_level.txt ================================================ FILE: DenseFusion/lib/knn/knn_pytorch.egg-info/dependency_links.txt ================================================ ================================================ FILE: DenseFusion/lib/knn/knn_pytorch.egg-info/top_level.txt ================================================ knn_pytorch ================================================ FILE: DenseFusion/lib/knn/knn_pytorch.py ================================================ def __bootstrap__(): global __bootstrap__, __loader__, __file__ import sys, pkg_resources, imp __file__ = pkg_resources.resource_filename(__name__, 'knn_pytorch.cpython-35m-x86_64-linux-gnu.so') __loader__ = None; del __bootstrap__, __loader__ imp.load_dynamic(__name__,__file__) __bootstrap__() ================================================ FILE: DenseFusion/lib/knn/setup.py ================================================ #!/usr/bin/env python import glob import os import torch from setuptools import find_packages from setuptools import setup from torch.utils.cpp_extension import CUDA_HOME from torch.utils.cpp_extension import CppExtension from torch.utils.cpp_extension import CUDAExtension requirements = ["torch", "torchvision"] def get_extensions(): this_dir = os.path.dirname(os.path.abspath(__file__)) extensions_dir = os.path.join(this_dir, "src") main_file = glob.glob(os.path.join(extensions_dir, "*.cpp")) source_cpu = glob.glob(os.path.join(extensions_dir, "cpu", "*.cpp")) source_cuda = glob.glob(os.path.join(extensions_dir, "cuda", "*.cu")) sources = main_file + source_cpu extension = CppExtension extra_compile_args = {"cxx": []} define_macros = [] if torch.cuda.is_available() and CUDA_HOME is not None: extension = CUDAExtension sources += source_cuda define_macros += [("WITH_CUDA", None)] extra_compile_args["nvcc"] = [ "-DCUDA_HAS_FP16=1", "-D__CUDA_NO_HALF_OPERATORS__", "-D__CUDA_NO_HALF_CONVERSIONS__", "-D__CUDA_NO_HALF2_OPERATORS__", ] sources = [os.path.join(extensions_dir, s) for s in sources] include_dirs = [extensions_dir] ext_modules = [ extension( "knn_pytorch.knn_pytorch", sources, include_dirs=include_dirs, define_macros=define_macros, extra_compile_args=extra_compile_args, ) ] return ext_modules setup( name="knn_pytorch", version="0.1", author="foolyc", url="https://github.com/foolyc/torchKNN", description="KNN implement in Pytorch 1.0 including both cpu version and gpu version", ext_modules=get_extensions(), cmdclass={"build_ext": torch.utils.cpp_extension.BuildExtension}, ) ================================================ FILE: DenseFusion/lib/knn/src/cpu/knn_cpu.cpp ================================================ #include "cpu/vision.h" void knn_cpu(float* ref_dev, int ref_width, float* query_dev, int query_width, int height, int k, float* dist_dev, long* ind_dev, long* ind_buf) { // Compute all the distances for(int query_idx = 0;query_idx dist_dev[query_idx * ref_width + j + 1]) { temp_value = dist_dev[query_idx * ref_width + j]; dist_dev[query_idx * ref_width + j] = dist_dev[query_idx * ref_width + j + 1]; dist_dev[query_idx * ref_width + j + 1] = temp_value; temp_idx = ind_buf[j]; ind_buf[j] = ind_buf[j + 1]; ind_buf[j + 1] = temp_idx; } } for(int i = 0;i < k;i++) ind_dev[query_idx + i * query_width] = ind_buf[i]; #if DEBUG for(int i = 0;i < ref_width;i++) printf("%d, ", ind_buf[i]); printf("\n"); #endif } } ================================================ FILE: DenseFusion/lib/knn/src/cpu/vision.h ================================================ #pragma once #include void knn_cpu(float* ref_dev, int ref_width, float* query_dev, int query_width, int height, int k, float* dist_dev, long* ind_dev, long* ind_buf); ================================================ FILE: DenseFusion/lib/knn/src/cuda/knn.cu ================================================ /** Modifed version of knn-CUDA from https://github.com/vincentfpgarcia/kNN-CUDA * The modifications are * removed texture memory usage * removed split query KNN computation * added feature extraction with bilinear interpolation * * Last modified by Christopher B. Choy 12/23/2016 */ // Includes #include #include "cuda.h" #define IDX2D(i, j, dj) (dj * i + j) #define IDX3D(i, j, k, dj, dk) (IDX2D(IDX2D(i, j, dj), k, dk)) #define BLOCK 512 #define MAX_STREAMS 512 // Constants used by the program #define BLOCK_DIM 16 #define DEBUG 0 /** * Computes the distance between two matrix A (reference points) and * B (query points) containing respectively wA and wB points. * * @param A pointer on the matrix A * @param wA width of the matrix A = number of points in A * @param B pointer on the matrix B * @param wB width of the matrix B = number of points in B * @param dim dimension of points = height of matrices A and B * @param AB pointer on the matrix containing the wA*wB distances computed */ __global__ void cuComputeDistanceGlobal( float* A, int wA, float* B, int wB, int dim, float* AB){ // Declaration of the shared memory arrays As and Bs used to store the sub-matrix of A and B __shared__ float shared_A[BLOCK_DIM][BLOCK_DIM]; __shared__ float shared_B[BLOCK_DIM][BLOCK_DIM]; // Sub-matrix of A (begin, step, end) and Sub-matrix of B (begin, step) __shared__ int begin_A; __shared__ int begin_B; __shared__ int step_A; __shared__ int step_B; __shared__ int end_A; // Thread index int tx = threadIdx.x; int ty = threadIdx.y; // Other variables float tmp; float ssd = 0; // Loop parameters begin_A = BLOCK_DIM * blockIdx.y; begin_B = BLOCK_DIM * blockIdx.x; step_A = BLOCK_DIM * wA; step_B = BLOCK_DIM * wB; end_A = begin_A + (dim-1) * wA; // Conditions int cond0 = (begin_A + tx < wA); // used to write in shared memory int cond1 = (begin_B + tx < wB); // used to write in shared memory & to computations and to write in output matrix int cond2 = (begin_A + ty < wA); // used to computations and to write in output matrix // Loop over all the sub-matrices of A and B required to compute the block sub-matrix for (int a = begin_A, b = begin_B; a <= end_A; a += step_A, b += step_B) { // Load the matrices from device memory to shared memory; each thread loads one element of each matrix if (a/wA + ty < dim){ shared_A[ty][tx] = (cond0)? A[a + wA * ty + tx] : 0; shared_B[ty][tx] = (cond1)? B[b + wB * ty + tx] : 0; } else{ shared_A[ty][tx] = 0; shared_B[ty][tx] = 0; } // Synchronize to make sure the matrices are loaded __syncthreads(); // Compute the difference between the two matrixes; each thread computes one element of the block sub-matrix if (cond2 && cond1){ for (int k = 0; k < BLOCK_DIM; ++k){ tmp = shared_A[k][ty] - shared_B[k][tx]; ssd += tmp*tmp; } } // Synchronize to make sure that the preceding computation is done before loading two new sub-matrices of A and B in the next iteration __syncthreads(); } // Write the block sub-matrix to device memory; each thread writes one element if (cond2 && cond1) AB[(begin_A + ty) * wB + begin_B + tx] = ssd; } /** * Gathers k-th smallest distances for each column of the distance matrix in the top. * * @param dist distance matrix * @param ind index matrix * @param width width of the distance matrix and of the index matrix * @param height height of the distance matrix and of the index matrix * @param k number of neighbors to consider */ __global__ void cuInsertionSort(float *dist, long *ind, int width, int height, int k){ // Variables int l, i, j; float *p_dist; long *p_ind; float curr_dist, max_dist; long curr_row, max_row; unsigned int xIndex = blockIdx.x * blockDim.x + threadIdx.x; if (xIndexcurr_dist){ i=a; break; } } for (j=l; j>i; j--){ p_dist[j*width] = p_dist[(j-1)*width]; p_ind[j*width] = p_ind[(j-1)*width]; } p_dist[i*width] = curr_dist; p_ind[i*width] = l+1; } else { p_ind[l*width] = l+1; } max_dist = p_dist[curr_row]; } // Part 2 : insert element in the k-th first lines max_row = (k-1)*width; for (l=k; lcurr_dist){ i=a; break; } } for (j=k-1; j>i; j--){ p_dist[j*width] = p_dist[(j-1)*width]; p_ind[j*width] = p_ind[(j-1)*width]; } p_dist[i*width] = curr_dist; p_ind[i*width] = l+1; max_dist = p_dist[max_row]; } } } } /** * Computes the square root of the first line (width-th first element) * of the distance matrix. * * @param dist distance matrix * @param width width of the distance matrix * @param k number of neighbors to consider */ __global__ void cuParallelSqrt(float *dist, int width, int k){ unsigned int xIndex = blockIdx.x * blockDim.x + threadIdx.x; unsigned int yIndex = blockIdx.y * blockDim.y + threadIdx.y; if (xIndex>>(ref_dev, ref_nb, query_dev, query_nb, dim, dist_dev); // Kernel 2: Sort each column cuInsertionSort<<>>(dist_dev, ind_dev, query_nb, ref_nb, k); // Kernel 3: Compute square root of k first elements // cuParallelSqrt<<>>(dist_dev, query_nb, k); #if DEBUG unsigned int size_of_float = sizeof(float); unsigned long size_of_long = sizeof(long); float* dist_host = new float[query_nb * k]; long* idx_host = new long[query_nb * k]; // Memory copy of output from device to host cudaMemcpy(&dist_host[0], dist_dev, query_nb * k *size_of_float, cudaMemcpyDeviceToHost); cudaMemcpy(&idx_host[0], ind_dev, query_nb * k * size_of_long, cudaMemcpyDeviceToHost); int i = 0; for(i = 0; i < 100; i++){ printf("IDX[%d]: %d\n", i, (int)idx_host[i]); } #endif } ================================================ FILE: DenseFusion/lib/knn/src/cuda/vision.h ================================================ #pragma once #include #include void knn_device(float* ref_dev, int ref_width, float* query_dev, int query_width, int height, int k, float* dist_dev, long* ind_dev, cudaStream_t stream); ================================================ FILE: DenseFusion/lib/knn/src/knn.h ================================================ #pragma once #include "cpu/vision.h" #ifdef WITH_CUDA #include "cuda/vision.h" #include extern THCState *state; #endif int knn(at::Tensor& ref, at::Tensor& query, at::Tensor& idx) { // TODO check dimensions long batch, ref_nb, query_nb, dim, k; batch = ref.size(0); dim = ref.size(1); k = idx.size(1); ref_nb = ref.size(2); query_nb = query.size(2); float *ref_dev = ref.data(); float *query_dev = query.data(); long *idx_dev = idx.data(); if (ref.type().is_cuda()) { #ifdef WITH_CUDA // TODO raise error if not compiled with CUDA float *dist_dev = (float*)THCudaMalloc(state, ref_nb * query_nb * sizeof(float)); for (int b = 0; b < batch; b++) { knn_device(ref_dev + b * dim * ref_nb, ref_nb, query_dev + b * dim * query_nb, query_nb, dim, k, dist_dev, idx_dev + b * k * query_nb, THCState_getCurrentStream(state)); } THCudaFree(state, dist_dev); cudaError_t err = cudaGetLastError(); if (err != cudaSuccess) { printf("error in knn: %s\n", cudaGetErrorString(err)); THError("aborting"); } return 1; #else AT_ERROR("Not compiled with GPU support"); #endif } float *dist_dev = (float*)malloc(ref_nb * query_nb * sizeof(float)); long *ind_buf = (long*)malloc(ref_nb * sizeof(long)); for (int b = 0; b < batch; b++) { knn_cpu(ref_dev + b * dim * ref_nb, ref_nb, query_dev + b * dim * query_nb, query_nb, dim, k, dist_dev, idx_dev + b * k * query_nb, ind_buf); } free(dist_dev); free(ind_buf); return 1; } ================================================ FILE: DenseFusion/lib/knn/src/vision.cpp ================================================ #include "knn.h" PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { m.def("knn", &knn, "k-nearest neighbors"); } ================================================ FILE: DenseFusion/lib/loss.py ================================================ from torch.nn.modules.loss import _Loss from torch.autograd import Variable import torch import time import numpy as np import torch.nn as nn import random import torch.backends.cudnn as cudnn from lib.knn.__init__ import KNearestNeighbor def loss_calculation(pred_r, pred_t, pred_c, target, model_points, idx, points, w, refine, num_point_mesh, sym_list): knn = KNearestNeighbor(1) bs, num_p, _ = pred_c.size() pred_r = pred_r / (torch.norm(pred_r, dim=2).view(bs, num_p, 1)) base = torch.cat(((1.0 - 2.0*(pred_r[:, :, 2]**2 + pred_r[:, :, 3]**2)).view(bs, num_p, 1),\ (2.0*pred_r[:, :, 1]*pred_r[:, :, 2] - 2.0*pred_r[:, :, 0]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 0]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 1]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 1]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 3]*pred_r[:, :, 0]).view(bs, num_p, 1), \ (1.0 - 2.0*(pred_r[:, :, 1]**2 + pred_r[:, :, 3]**2)).view(bs, num_p, 1), \ (-2.0*pred_r[:, :, 0]*pred_r[:, :, 1] + 2.0*pred_r[:, :, 2]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (-2.0*pred_r[:, :, 0]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 1]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 0]*pred_r[:, :, 1] + 2.0*pred_r[:, :, 2]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (1.0 - 2.0*(pred_r[:, :, 1]**2 + pred_r[:, :, 2]**2)).view(bs, num_p, 1)), dim=2).contiguous().view(bs * num_p, 3, 3) ori_base = base base = base.contiguous().transpose(2, 1).contiguous() model_points = model_points.view(bs, 1, num_point_mesh, 3).repeat(1, num_p, 1, 1).view(bs * num_p, num_point_mesh, 3) target = target.view(bs, 1, num_point_mesh, 3).repeat(1, num_p, 1, 1).view(bs * num_p, num_point_mesh, 3) ori_target = target pred_t = pred_t.contiguous().view(bs * num_p, 1, 3) ori_t = pred_t points = points.contiguous().view(bs * num_p, 1, 3) pred_c = pred_c.contiguous().view(bs * num_p) pred = torch.add(torch.bmm(model_points, base), points + pred_t) if not refine: if idx[0].item() in sym_list: target = target[0].transpose(1, 0).contiguous().view(3, -1) pred = pred.permute(2, 0, 1).contiguous().view(3, -1) inds = knn(target.unsqueeze(0), pred.unsqueeze(0)) target = torch.index_select(target, 1, inds.view(-1).detach() - 1) target = target.view(3, bs * num_p, num_point_mesh).permute(1, 2, 0).contiguous() pred = pred.view(3, bs * num_p, num_point_mesh).permute(1, 2, 0).contiguous() dis = torch.mean(torch.norm((pred - target), dim=2), dim=1) loss = torch.mean((dis * pred_c - w * torch.log(pred_c)), dim=0) pred_c = pred_c.view(bs, num_p) how_max, which_max = torch.max(pred_c, 1) dis = dis.view(bs, num_p) t = ori_t[which_max[0]] + points[which_max[0]] points = points.view(1, bs * num_p, 3) ori_base = ori_base[which_max[0]].view(1, 3, 3).contiguous() ori_t = t.repeat(bs * num_p, 1).contiguous().view(1, bs * num_p, 3) new_points = torch.bmm((points - ori_t), ori_base).contiguous() new_target = ori_target[0].view(1, num_point_mesh, 3).contiguous() ori_t = t.repeat(num_point_mesh, 1).contiguous().view(1, num_point_mesh, 3) new_target = torch.bmm((new_target - ori_t), ori_base).contiguous() # print('------------> ', dis[0][which_max[0]].item(), pred_c[0][which_max[0]].item(), idx[0].item()) del knn return loss, dis[0][which_max[0]], new_points.detach(), new_target.detach() class Loss(_Loss): def __init__(self, num_points_mesh, sym_list): super(Loss, self).__init__(True) self.num_pt_mesh = num_points_mesh self.sym_list = sym_list def forward(self, pred_r, pred_t, pred_c, target, model_points, idx, points, w, refine): return loss_calculation(pred_r, pred_t, pred_c, target, model_points, idx, points, w, refine, self.num_pt_mesh, self.sym_list) ================================================ FILE: DenseFusion/lib/loss_refiner.py ================================================ from torch.nn.modules.loss import _Loss from torch.autograd import Variable import torch import time import numpy as np import torch.nn as nn import random import torch.backends.cudnn as cudnn from lib.knn.__init__ import KNearestNeighbor def loss_calculation(pred_r, pred_t, target, model_points, idx, points, num_point_mesh, sym_list): knn = KNearestNeighbor(1) pred_r = pred_r.view(1, 1, -1) pred_t = pred_t.view(1, 1, -1) bs, num_p, _ = pred_r.size() num_input_points = len(points[0]) pred_r = pred_r / (torch.norm(pred_r, dim=2).view(bs, num_p, 1)) base = torch.cat(((1.0 - 2.0*(pred_r[:, :, 2]**2 + pred_r[:, :, 3]**2)).view(bs, num_p, 1),\ (2.0*pred_r[:, :, 1]*pred_r[:, :, 2] - 2.0*pred_r[:, :, 0]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 0]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 1]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 1]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 3]*pred_r[:, :, 0]).view(bs, num_p, 1), \ (1.0 - 2.0*(pred_r[:, :, 1]**2 + pred_r[:, :, 3]**2)).view(bs, num_p, 1), \ (-2.0*pred_r[:, :, 0]*pred_r[:, :, 1] + 2.0*pred_r[:, :, 2]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (-2.0*pred_r[:, :, 0]*pred_r[:, :, 2] + 2.0*pred_r[:, :, 1]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (2.0*pred_r[:, :, 0]*pred_r[:, :, 1] + 2.0*pred_r[:, :, 2]*pred_r[:, :, 3]).view(bs, num_p, 1), \ (1.0 - 2.0*(pred_r[:, :, 1]**2 + pred_r[:, :, 2]**2)).view(bs, num_p, 1)), dim=2).contiguous().view(bs * num_p, 3, 3) ori_base = base base = base.contiguous().transpose(2, 1).contiguous() model_points = model_points.view(bs, 1, num_point_mesh, 3).repeat(1, num_p, 1, 1).view(bs * num_p, num_point_mesh, 3) target = target.view(bs, 1, num_point_mesh, 3).repeat(1, num_p, 1, 1).view(bs * num_p, num_point_mesh, 3) ori_target = target pred_t = pred_t.contiguous().view(bs * num_p, 1, 3) ori_t = pred_t pred = torch.add(torch.bmm(model_points, base), pred_t) if idx[0].item() in sym_list: target = target[0].transpose(1, 0).contiguous().view(3, -1) pred = pred.permute(2, 0, 1).contiguous().view(3, -1) inds = knn(target.unsqueeze(0), pred.unsqueeze(0)) target = torch.index_select(target, 1, inds.view(-1).detach() - 1) target = target.view(3, bs * num_p, num_point_mesh).permute(1, 2, 0).contiguous() pred = pred.view(3, bs * num_p, num_point_mesh).permute(1, 2, 0).contiguous() dis = torch.mean(torch.norm((pred - target), dim=2), dim=1) t = ori_t[0] points = points.view(1, num_input_points, 3) ori_base = ori_base[0].view(1, 3, 3).contiguous() ori_t = t.repeat(bs * num_input_points, 1).contiguous().view(1, bs * num_input_points, 3) new_points = torch.bmm((points - ori_t), ori_base).contiguous() new_target = ori_target[0].view(1, num_point_mesh, 3).contiguous() ori_t = t.repeat(num_point_mesh, 1).contiguous().view(1, num_point_mesh, 3) new_target = torch.bmm((new_target - ori_t), ori_base).contiguous() # print('------------> ', dis.item(), idx[0].item()) del knn return dis, new_points.detach(), new_target.detach() class Loss_refine(_Loss): def __init__(self, num_points_mesh, sym_list): super(Loss_refine, self).__init__(True) self.num_pt_mesh = num_points_mesh self.sym_list = sym_list def forward(self, pred_r, pred_t, target, model_points, idx, points): return loss_calculation(pred_r, pred_t, target, model_points, idx, points, self.num_pt_mesh, self.sym_list) ================================================ FILE: DenseFusion/lib/network.py ================================================ import argparse import os import random import torch import torch.nn as nn import torch.nn.parallel import torch.backends.cudnn as cudnn import torch.optim as optim import torch.utils.data import torchvision.transforms as transforms import torchvision.utils as vutils from torch.autograd import Variable from PIL import Image import numpy as np import pdb import torch.nn.functional as F from lib.pspnet import PSPNet psp_models = { 'resnet18': lambda: PSPNet(sizes=(1, 2, 3, 6), psp_size=512, deep_features_size=256, backend='resnet18'), 'resnet34': lambda: PSPNet(sizes=(1, 2, 3, 6), psp_size=512, deep_features_size=256, backend='resnet34'), 'resnet50': lambda: PSPNet(sizes=(1, 2, 3, 6), psp_size=2048, deep_features_size=1024, backend='resnet50'), 'resnet101': lambda: PSPNet(sizes=(1, 2, 3, 6), psp_size=2048, deep_features_size=1024, backend='resnet101'), 'resnet152': lambda: PSPNet(sizes=(1, 2, 3, 6), psp_size=2048, deep_features_size=1024, backend='resnet152') } class ModifiedResnet(nn.Module): def __init__(self, usegpu=True): super(ModifiedResnet, self).__init__() self.model = psp_models['resnet18'.lower()]() self.model = nn.DataParallel(self.model) def forward(self, x): x = self.model(x) return x class PoseNetFeat(nn.Module): def __init__(self, num_points): super(PoseNetFeat, self).__init__() self.conv1 = torch.nn.Conv1d(3, 64, 1) self.conv2 = torch.nn.Conv1d(64, 128, 1) self.e_conv1 = torch.nn.Conv1d(32, 64, 1) self.e_conv2 = torch.nn.Conv1d(64, 128, 1) self.conv5 = torch.nn.Conv1d(256, 512, 1) self.conv6 = torch.nn.Conv1d(512, 1024, 1) self.ap1 = torch.nn.AvgPool1d(num_points) self.num_points = num_points def forward(self, x, emb): x = F.relu(self.conv1(x)) emb = F.relu(self.e_conv1(emb)) pointfeat_1 = torch.cat((x, emb), dim=1) x = F.relu(self.conv2(x)) emb = F.relu(self.e_conv2(emb)) pointfeat_2 = torch.cat((x, emb), dim=1) x = F.relu(self.conv5(pointfeat_2)) x = F.relu(self.conv6(x)) ap_x = self.ap1(x) ap_x = ap_x.view(-1, 1024, 1).repeat(1, 1, self.num_points) return torch.cat([pointfeat_1, pointfeat_2, ap_x], 1) #128 + 256 + 1024 class PoseNet(nn.Module): def __init__(self, num_points, num_obj): super(PoseNet, self).__init__() self.num_points = num_points self.cnn = ModifiedResnet() self.feat = PoseNetFeat(num_points) self.conv1_r = torch.nn.Conv1d(1408, 640, 1) self.conv1_t = torch.nn.Conv1d(1408, 640, 1) self.conv1_c = torch.nn.Conv1d(1408, 640, 1) self.conv2_r = torch.nn.Conv1d(640, 256, 1) self.conv2_t = torch.nn.Conv1d(640, 256, 1) self.conv2_c = torch.nn.Conv1d(640, 256, 1) self.conv3_r = torch.nn.Conv1d(256, 128, 1) self.conv3_t = torch.nn.Conv1d(256, 128, 1) self.conv3_c = torch.nn.Conv1d(256, 128, 1) self.conv4_r = torch.nn.Conv1d(128, num_obj*4, 1) #quaternion self.conv4_t = torch.nn.Conv1d(128, num_obj*3, 1) #translation self.conv4_c = torch.nn.Conv1d(128, num_obj*1, 1) #confidence self.num_obj = num_obj def forward(self, img, x, choose, obj): out_img = self.cnn(img) bs, di, _, _ = out_img.size() emb = out_img.view(bs, di, -1) choose = choose.repeat(1, di, 1) emb = torch.gather(emb, 2, choose).contiguous() x = x.transpose(2, 1).contiguous() ap_x = self.feat(x, emb) rx = F.relu(self.conv1_r(ap_x)) tx = F.relu(self.conv1_t(ap_x)) cx = F.relu(self.conv1_c(ap_x)) rx = F.relu(self.conv2_r(rx)) tx = F.relu(self.conv2_t(tx)) cx = F.relu(self.conv2_c(cx)) rx = F.relu(self.conv3_r(rx)) tx = F.relu(self.conv3_t(tx)) cx = F.relu(self.conv3_c(cx)) rx = self.conv4_r(rx).view(bs, self.num_obj, 4, self.num_points) tx = self.conv4_t(tx).view(bs, self.num_obj, 3, self.num_points) cx = torch.sigmoid(self.conv4_c(cx)).view(bs, self.num_obj, 1, self.num_points) b = 0 out_rx = torch.index_select(rx[b], 0, obj[b]) out_tx = torch.index_select(tx[b], 0, obj[b]) out_cx = torch.index_select(cx[b], 0, obj[b]) out_rx = out_rx.contiguous().transpose(2, 1).contiguous() out_cx = out_cx.contiguous().transpose(2, 1).contiguous() out_tx = out_tx.contiguous().transpose(2, 1).contiguous() return out_rx, out_tx, out_cx, emb.detach() class PoseRefineNetFeat(nn.Module): def __init__(self, num_points): super(PoseRefineNetFeat, self).__init__() self.conv1 = torch.nn.Conv1d(3, 64, 1) self.conv2 = torch.nn.Conv1d(64, 128, 1) self.e_conv1 = torch.nn.Conv1d(32, 64, 1) self.e_conv2 = torch.nn.Conv1d(64, 128, 1) self.conv5 = torch.nn.Conv1d(384, 512, 1) self.conv6 = torch.nn.Conv1d(512, 1024, 1) self.ap1 = torch.nn.AvgPool1d(num_points) self.num_points = num_points def forward(self, x, emb): x = F.relu(self.conv1(x)) emb = F.relu(self.e_conv1(emb)) pointfeat_1 = torch.cat([x, emb], dim=1) x = F.relu(self.conv2(x)) emb = F.relu(self.e_conv2(emb)) pointfeat_2 = torch.cat([x, emb], dim=1) pointfeat_3 = torch.cat([pointfeat_1, pointfeat_2], dim=1) x = F.relu(self.conv5(pointfeat_3)) x = F.relu(self.conv6(x)) ap_x = self.ap1(x) ap_x = ap_x.view(-1, 1024) return ap_x class PoseRefineNet(nn.Module): def __init__(self, num_points, num_obj): super(PoseRefineNet, self).__init__() self.num_points = num_points self.feat = PoseRefineNetFeat(num_points) self.conv1_r = torch.nn.Linear(1024, 512) self.conv1_t = torch.nn.Linear(1024, 512) self.conv2_r = torch.nn.Linear(512, 128) self.conv2_t = torch.nn.Linear(512, 128) self.conv3_r = torch.nn.Linear(128, num_obj*4) #quaternion self.conv3_t = torch.nn.Linear(128, num_obj*3) #translation self.num_obj = num_obj def forward(self, x, emb, obj): bs = x.size()[0] x = x.transpose(2, 1).contiguous() ap_x = self.feat(x, emb) rx = F.relu(self.conv1_r(ap_x)) tx = F.relu(self.conv1_t(ap_x)) rx = F.relu(self.conv2_r(rx)) tx = F.relu(self.conv2_t(tx)) rx = self.conv3_r(rx).view(bs, self.num_obj, 4) tx = self.conv3_t(tx).view(bs, self.num_obj, 3) b = 0 out_rx = torch.index_select(rx[b], 0, obj[b]) out_tx = torch.index_select(tx[b], 0, obj[b]) return out_rx, out_tx ================================================ FILE: DenseFusion/lib/pspnet.py ================================================ import torch from torch import nn from torch.nn import functional as F import lib.extractors as extractors class PSPModule(nn.Module): def __init__(self, features, out_features=1024, sizes=(1, 2, 3, 6)): super(PSPModule, self).__init__() self.stages = [] self.stages = nn.ModuleList([self._make_stage(features, size) for size in sizes]) self.bottleneck = nn.Conv2d(features * (len(sizes) + 1), out_features, kernel_size=1) self.relu = nn.ReLU() def _make_stage(self, features, size): prior = nn.AdaptiveAvgPool2d(output_size=(size, size)) conv = nn.Conv2d(features, features, kernel_size=1, bias=False) return nn.Sequential(prior, conv) def forward(self, feats): h, w = feats.size(2), feats.size(3) priors = [F.upsample(input=stage(feats), size=(h, w), mode='bilinear') for stage in self.stages] + [feats] bottle = self.bottleneck(torch.cat(priors, 1)) return self.relu(bottle) class PSPUpsample(nn.Module): def __init__(self, in_channels, out_channels): super(PSPUpsample, self).__init__() self.conv = nn.Sequential( nn.Upsample(scale_factor=2, mode='bilinear', align_corners=True), nn.Conv2d(in_channels, out_channels, 3, padding=1), nn.PReLU() ) def forward(self, x): return self.conv(x) class PSPNet(nn.Module): def __init__(self, n_classes=21, sizes=(1, 2, 3, 6), psp_size=2048, deep_features_size=1024, backend='resnet18', pretrained=False): super(PSPNet, self).__init__() self.feats = getattr(extractors, backend)(pretrained) self.psp = PSPModule(psp_size, 1024, sizes) self.drop_1 = nn.Dropout2d(p=0.3) self.up_1 = PSPUpsample(1024, 256) self.up_2 = PSPUpsample(256, 64) self.up_3 = PSPUpsample(64, 64) self.drop_2 = nn.Dropout2d(p=0.15) self.final = nn.Sequential( nn.Conv2d(64, 32, kernel_size=1), nn.LogSoftmax() ) self.classifier = nn.Sequential( nn.Linear(deep_features_size, 256), nn.ReLU(), nn.Linear(256, n_classes) ) def forward(self, x): f, class_f = self.feats(x) p = self.psp(f) p = self.drop_1(p) p = self.up_1(p) p = self.drop_2(p) p = self.up_2(p) p = self.drop_2(p) p = self.up_3(p) return self.final(p) ================================================ FILE: DenseFusion/lib/transformations.py ================================================ # -*- coding: utf-8 -*- # transformations.py # Copyright (c) 2006-2018, Christoph Gohlke # Copyright (c) 2006-2018, The Regents of the University of California # Produced at the Laboratory for Fluorescence Dynamics # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # * Neither the name of the copyright holders nor the names of any # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. """Homogeneous Transformation Matrices and Quaternions. A library for calculating 4x4 matrices for translating, rotating, reflecting, scaling, shearing, projecting, orthogonalizing, and superimposing arrays of 3D homogeneous coordinates as well as for converting between rotation matrices, Euler angles, and quaternions. Also includes an Arcball control object and functions to decompose transformation matrices. :Author: `Christoph Gohlke `_ :Organization: Laboratory for Fluorescence Dynamics, University of California, Irvine :Version: 2018.02.08 Requirements ------------ * `CPython 2.7 or 3.6 `_ * `Numpy 1.13 `_ * `Transformations.c 2018.02.08 `_ (recommended for speedup of some functions) Notes ----- The API is not stable yet and is expected to change between revisions. This Python code is not optimized for speed. Refer to the transformations.c module for a faster implementation of some functions. Documentation in HTML format can be generated with epydoc. Matrices (M) can be inverted using numpy.linalg.inv(M), be concatenated using numpy.dot(M0, M1), or transform homogeneous coordinate arrays (v) using numpy.dot(M, v) for shape (4, \*) column vectors, respectively numpy.dot(v, M.T) for shape (\*, 4) row vectors ("array of points"). This module follows the "column vectors on the right" and "row major storage" (C contiguous) conventions. The translation components are in the right column of the transformation matrix, i.e. M[:3, 3]. The transpose of the transformation matrices may have to be used to interface with other graphics systems, e.g. with OpenGL's glMultMatrixd(). See also [16]. Calculations are carried out with numpy.float64 precision. Vector, point, quaternion, and matrix function arguments are expected to be "array like", i.e. tuple, list, or numpy arrays. Return types are numpy arrays unless specified otherwise. Angles are in radians unless specified otherwise. Quaternions w+ix+jy+kz are represented as [w, x, y, z]. A triple of Euler angles can be applied/interpreted in 24 ways, which can be specified using a 4 character string or encoded 4-tuple: *Axes 4-string*: e.g. 'sxyz' or 'ryxy' - first character : rotations are applied to 's'tatic or 'r'otating frame - remaining characters : successive rotation axis 'x', 'y', or 'z' *Axes 4-tuple*: e.g. (0, 0, 0, 0) or (1, 1, 1, 1) - inner axis: code of axis ('x':0, 'y':1, 'z':2) of rightmost matrix. - parity : even (0) if inner axis 'x' is followed by 'y', 'y' is followed by 'z', or 'z' is followed by 'x'. Otherwise odd (1). - repetition : first and last axis are same (1) or different (0). - frame : rotations are applied to static (0) or rotating (1) frame. Other Python packages and modules for 3D transformations and quaternions: * `Transforms3d `_ includes most code of this module. * `Blender.mathutils `_ * `numpy-dtypes `_ References ---------- (1) Matrices and transformations. Ronald Goldman. In "Graphics Gems I", pp 472-475. Morgan Kaufmann, 1990. (2) More matrices and transformations: shear and pseudo-perspective. Ronald Goldman. In "Graphics Gems II", pp 320-323. Morgan Kaufmann, 1991. (3) Decomposing a matrix into simple transformations. Spencer Thomas. In "Graphics Gems II", pp 320-323. Morgan Kaufmann, 1991. (4) Recovering the data from the transformation matrix. Ronald Goldman. In "Graphics Gems II", pp 324-331. Morgan Kaufmann, 1991. (5) Euler angle conversion. Ken Shoemake. In "Graphics Gems IV", pp 222-229. Morgan Kaufmann, 1994. (6) Arcball rotation control. Ken Shoemake. In "Graphics Gems IV", pp 175-192. Morgan Kaufmann, 1994. (7) Representing attitude: Euler angles, unit quaternions, and rotation vectors. James Diebel. 2006. (8) A discussion of the solution for the best rotation to relate two sets of vectors. W Kabsch. Acta Cryst. 1978. A34, 827-828. (9) Closed-form solution of absolute orientation using unit quaternions. BKP Horn. J Opt Soc Am A. 1987. 4(4):629-642. (10) Quaternions. Ken Shoemake. http://www.sfu.ca/~jwa3/cmpt461/files/quatut.pdf (11) From quaternion to matrix and back. JMP van Waveren. 2005. http://www.intel.com/cd/ids/developer/asmo-na/eng/293748.htm (12) Uniform random rotations. Ken Shoemake. In "Graphics Gems III", pp 124-132. Morgan Kaufmann, 1992. (13) Quaternion in molecular modeling. CFF Karney. J Mol Graph Mod, 25(5):595-604 (14) New method for extracting the quaternion from a rotation matrix. Itzhack Y Bar-Itzhack, J Guid Contr Dynam. 2000. 23(6): 1085-1087. (15) Multiple View Geometry in Computer Vision. Hartley and Zissermann. Cambridge University Press; 2nd Ed. 2004. Chapter 4, Algorithm 4.7, p 130. (16) Column Vectors vs. Row Vectors. http://steve.hollasch.net/cgindex/math/matrix/column-vec.html Examples -------- >>> alpha, beta, gamma = 0.123, -1.234, 2.345 >>> origin, xaxis, yaxis, zaxis = [0, 0, 0], [1, 0, 0], [0, 1, 0], [0, 0, 1] >>> I = identity_matrix() >>> Rx = rotation_matrix(alpha, xaxis) >>> Ry = rotation_matrix(beta, yaxis) >>> Rz = rotation_matrix(gamma, zaxis) >>> R = concatenate_matrices(Rx, Ry, Rz) >>> euler = euler_from_matrix(R, 'rxyz') >>> numpy.allclose([alpha, beta, gamma], euler) True >>> Re = euler_matrix(alpha, beta, gamma, 'rxyz') >>> is_same_transform(R, Re) True >>> al, be, ga = euler_from_matrix(Re, 'rxyz') >>> is_same_transform(Re, euler_matrix(al, be, ga, 'rxyz')) True >>> qx = quaternion_about_axis(alpha, xaxis) >>> qy = quaternion_about_axis(beta, yaxis) >>> qz = quaternion_about_axis(gamma, zaxis) >>> q = quaternion_multiply(qx, qy) >>> q = quaternion_multiply(q, qz) >>> Rq = quaternion_matrix(q) >>> is_same_transform(R, Rq) True >>> S = scale_matrix(1.23, origin) >>> T = translation_matrix([1, 2, 3]) >>> Z = shear_matrix(beta, xaxis, origin, zaxis) >>> R = random_rotation_matrix(numpy.random.rand(3)) >>> M = concatenate_matrices(T, R, Z, S) >>> scale, shear, angles, trans, persp = decompose_matrix(M) >>> numpy.allclose(scale, 1.23) True >>> numpy.allclose(trans, [1, 2, 3]) True >>> numpy.allclose(shear, [0, math.tan(beta), 0]) True >>> is_same_transform(R, euler_matrix(axes='sxyz', *angles)) True >>> M1 = compose_matrix(scale, shear, angles, trans, persp) >>> is_same_transform(M, M1) True >>> v0, v1 = random_vector(3), random_vector(3) >>> M = rotation_matrix(angle_between_vectors(v0, v1), vector_product(v0, v1)) >>> v2 = numpy.dot(v0, M[:3,:3].T) >>> numpy.allclose(unit_vector(v1), unit_vector(v2)) True """ from __future__ import division, print_function import math import numpy __version__ = '2018.02.08' __docformat__ = 'restructuredtext en' __all__ = () def identity_matrix(): """Return 4x4 identity/unit matrix. >>> I = identity_matrix() >>> numpy.allclose(I, numpy.dot(I, I)) True >>> numpy.sum(I), numpy.trace(I) (4.0, 4.0) >>> numpy.allclose(I, numpy.identity(4)) True """ return numpy.identity(4) def translation_matrix(direction): """Return matrix to translate by direction vector. >>> v = numpy.random.random(3) - 0.5 >>> numpy.allclose(v, translation_matrix(v)[:3, 3]) True """ M = numpy.identity(4) M[:3, 3] = direction[:3] return M def translation_from_matrix(matrix): """Return translation vector from translation matrix. >>> v0 = numpy.random.random(3) - 0.5 >>> v1 = translation_from_matrix(translation_matrix(v0)) >>> numpy.allclose(v0, v1) True """ return numpy.array(matrix, copy=False)[:3, 3].copy() def reflection_matrix(point, normal): """Return matrix to mirror at plane defined by point and normal vector. >>> v0 = numpy.random.random(4) - 0.5 >>> v0[3] = 1. >>> v1 = numpy.random.random(3) - 0.5 >>> R = reflection_matrix(v0, v1) >>> numpy.allclose(2, numpy.trace(R)) True >>> numpy.allclose(v0, numpy.dot(R, v0)) True >>> v2 = v0.copy() >>> v2[:3] += v1 >>> v3 = v0.copy() >>> v2[:3] -= v1 >>> numpy.allclose(v2, numpy.dot(R, v3)) True """ normal = unit_vector(normal[:3]) M = numpy.identity(4) M[:3, :3] -= 2.0 * numpy.outer(normal, normal) M[:3, 3] = (2.0 * numpy.dot(point[:3], normal)) * normal return M def reflection_from_matrix(matrix): """Return mirror plane point and normal vector from reflection matrix. >>> v0 = numpy.random.random(3) - 0.5 >>> v1 = numpy.random.random(3) - 0.5 >>> M0 = reflection_matrix(v0, v1) >>> point, normal = reflection_from_matrix(M0) >>> M1 = reflection_matrix(point, normal) >>> is_same_transform(M0, M1) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=False) # normal: unit eigenvector corresponding to eigenvalue -1 w, V = numpy.linalg.eig(M[:3, :3]) i = numpy.where(abs(numpy.real(w) + 1.0) < 1e-8)[0] if not len(i): raise ValueError('no unit eigenvector corresponding to eigenvalue -1') normal = numpy.real(V[:, i[0]]).squeeze() # point: any unit eigenvector corresponding to eigenvalue 1 w, V = numpy.linalg.eig(M) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not len(i): raise ValueError('no unit eigenvector corresponding to eigenvalue 1') point = numpy.real(V[:, i[-1]]).squeeze() point /= point[3] return point, normal def rotation_matrix(angle, direction, point=None): """Return matrix to rotate about axis defined by point and direction. >>> R = rotation_matrix(math.pi/2, [0, 0, 1], [1, 0, 0]) >>> numpy.allclose(numpy.dot(R, [0, 0, 0, 1]), [1, -1, 0, 1]) True >>> angle = (random.random() - 0.5) * (2*math.pi) >>> direc = numpy.random.random(3) - 0.5 >>> point = numpy.random.random(3) - 0.5 >>> R0 = rotation_matrix(angle, direc, point) >>> R1 = rotation_matrix(angle-2*math.pi, direc, point) >>> is_same_transform(R0, R1) True >>> R0 = rotation_matrix(angle, direc, point) >>> R1 = rotation_matrix(-angle, -direc, point) >>> is_same_transform(R0, R1) True >>> I = numpy.identity(4, numpy.float64) >>> numpy.allclose(I, rotation_matrix(math.pi*2, direc)) True >>> numpy.allclose(2, numpy.trace(rotation_matrix(math.pi/2, ... direc, point))) True """ sina = math.sin(angle) cosa = math.cos(angle) direction = unit_vector(direction[:3]) # rotation matrix around unit vector R = numpy.diag([cosa, cosa, cosa]) R += numpy.outer(direction, direction) * (1.0 - cosa) direction *= sina R += numpy.array([[ 0.0, -direction[2], direction[1]], [ direction[2], 0.0, -direction[0]], [-direction[1], direction[0], 0.0]]) M = numpy.identity(4) M[:3, :3] = R if point is not None: # rotation not around origin point = numpy.array(point[:3], dtype=numpy.float64, copy=False) M[:3, 3] = point - numpy.dot(R, point) return M def rotation_from_matrix(matrix): """Return rotation angle and axis from rotation matrix. >>> angle = (random.random() - 0.5) * (2*math.pi) >>> direc = numpy.random.random(3) - 0.5 >>> point = numpy.random.random(3) - 0.5 >>> R0 = rotation_matrix(angle, direc, point) >>> angle, direc, point = rotation_from_matrix(R0) >>> R1 = rotation_matrix(angle, direc, point) >>> is_same_transform(R0, R1) True """ R = numpy.array(matrix, dtype=numpy.float64, copy=False) R33 = R[:3, :3] # direction: unit eigenvector of R33 corresponding to eigenvalue of 1 w, W = numpy.linalg.eig(R33.T) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not len(i): raise ValueError('no unit eigenvector corresponding to eigenvalue 1') direction = numpy.real(W[:, i[-1]]).squeeze() # point: unit eigenvector of R33 corresponding to eigenvalue of 1 w, Q = numpy.linalg.eig(R) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not len(i): raise ValueError('no unit eigenvector corresponding to eigenvalue 1') point = numpy.real(Q[:, i[-1]]).squeeze() point /= point[3] # rotation angle depending on direction cosa = (numpy.trace(R33) - 1.0) / 2.0 if abs(direction[2]) > 1e-8: sina = (R[1, 0] + (cosa-1.0)*direction[0]*direction[1]) / direction[2] elif abs(direction[1]) > 1e-8: sina = (R[0, 2] + (cosa-1.0)*direction[0]*direction[2]) / direction[1] else: sina = (R[2, 1] + (cosa-1.0)*direction[1]*direction[2]) / direction[0] angle = math.atan2(sina, cosa) return angle, direction, point def scale_matrix(factor, origin=None, direction=None): """Return matrix to scale by factor around origin in direction. Use factor -1 for point symmetry. >>> v = (numpy.random.rand(4, 5) - 0.5) * 20 >>> v[3] = 1 >>> S = scale_matrix(-1.234) >>> numpy.allclose(numpy.dot(S, v)[:3], -1.234*v[:3]) True >>> factor = random.random() * 10 - 5 >>> origin = numpy.random.random(3) - 0.5 >>> direct = numpy.random.random(3) - 0.5 >>> S = scale_matrix(factor, origin) >>> S = scale_matrix(factor, origin, direct) """ if direction is None: # uniform scaling M = numpy.diag([factor, factor, factor, 1.0]) if origin is not None: M[:3, 3] = origin[:3] M[:3, 3] *= 1.0 - factor else: # nonuniform scaling direction = unit_vector(direction[:3]) factor = 1.0 - factor M = numpy.identity(4) M[:3, :3] -= factor * numpy.outer(direction, direction) if origin is not None: M[:3, 3] = (factor * numpy.dot(origin[:3], direction)) * direction return M def scale_from_matrix(matrix): """Return scaling factor, origin and direction from scaling matrix. >>> factor = random.random() * 10 - 5 >>> origin = numpy.random.random(3) - 0.5 >>> direct = numpy.random.random(3) - 0.5 >>> S0 = scale_matrix(factor, origin) >>> factor, origin, direction = scale_from_matrix(S0) >>> S1 = scale_matrix(factor, origin, direction) >>> is_same_transform(S0, S1) True >>> S0 = scale_matrix(factor, origin, direct) >>> factor, origin, direction = scale_from_matrix(S0) >>> S1 = scale_matrix(factor, origin, direction) >>> is_same_transform(S0, S1) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=False) M33 = M[:3, :3] factor = numpy.trace(M33) - 2.0 try: # direction: unit eigenvector corresponding to eigenvalue factor w, V = numpy.linalg.eig(M33) i = numpy.where(abs(numpy.real(w) - factor) < 1e-8)[0][0] direction = numpy.real(V[:, i]).squeeze() direction /= vector_norm(direction) except IndexError: # uniform scaling factor = (factor + 2.0) / 3.0 direction = None # origin: any eigenvector corresponding to eigenvalue 1 w, V = numpy.linalg.eig(M) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not len(i): raise ValueError('no eigenvector corresponding to eigenvalue 1') origin = numpy.real(V[:, i[-1]]).squeeze() origin /= origin[3] return factor, origin, direction def projection_matrix(point, normal, direction=None, perspective=None, pseudo=False): """Return matrix to project onto plane defined by point and normal. Using either perspective point, projection direction, or none of both. If pseudo is True, perspective projections will preserve relative depth such that Perspective = dot(Orthogonal, PseudoPerspective). >>> P = projection_matrix([0, 0, 0], [1, 0, 0]) >>> numpy.allclose(P[1:, 1:], numpy.identity(4)[1:, 1:]) True >>> point = numpy.random.random(3) - 0.5 >>> normal = numpy.random.random(3) - 0.5 >>> direct = numpy.random.random(3) - 0.5 >>> persp = numpy.random.random(3) - 0.5 >>> P0 = projection_matrix(point, normal) >>> P1 = projection_matrix(point, normal, direction=direct) >>> P2 = projection_matrix(point, normal, perspective=persp) >>> P3 = projection_matrix(point, normal, perspective=persp, pseudo=True) >>> is_same_transform(P2, numpy.dot(P0, P3)) True >>> P = projection_matrix([3, 0, 0], [1, 1, 0], [1, 0, 0]) >>> v0 = (numpy.random.rand(4, 5) - 0.5) * 20 >>> v0[3] = 1 >>> v1 = numpy.dot(P, v0) >>> numpy.allclose(v1[1], v0[1]) True >>> numpy.allclose(v1[0], 3-v1[1]) True """ M = numpy.identity(4) point = numpy.array(point[:3], dtype=numpy.float64, copy=False) normal = unit_vector(normal[:3]) if perspective is not None: # perspective projection perspective = numpy.array(perspective[:3], dtype=numpy.float64, copy=False) M[0, 0] = M[1, 1] = M[2, 2] = numpy.dot(perspective-point, normal) M[:3, :3] -= numpy.outer(perspective, normal) if pseudo: # preserve relative depth M[:3, :3] -= numpy.outer(normal, normal) M[:3, 3] = numpy.dot(point, normal) * (perspective+normal) else: M[:3, 3] = numpy.dot(point, normal) * perspective M[3, :3] = -normal M[3, 3] = numpy.dot(perspective, normal) elif direction is not None: # parallel projection direction = numpy.array(direction[:3], dtype=numpy.float64, copy=False) scale = numpy.dot(direction, normal) M[:3, :3] -= numpy.outer(direction, normal) / scale M[:3, 3] = direction * (numpy.dot(point, normal) / scale) else: # orthogonal projection M[:3, :3] -= numpy.outer(normal, normal) M[:3, 3] = numpy.dot(point, normal) * normal return M def projection_from_matrix(matrix, pseudo=False): """Return projection plane and perspective point from projection matrix. Return values are same as arguments for projection_matrix function: point, normal, direction, perspective, and pseudo. >>> point = numpy.random.random(3) - 0.5 >>> normal = numpy.random.random(3) - 0.5 >>> direct = numpy.random.random(3) - 0.5 >>> persp = numpy.random.random(3) - 0.5 >>> P0 = projection_matrix(point, normal) >>> result = projection_from_matrix(P0) >>> P1 = projection_matrix(*result) >>> is_same_transform(P0, P1) True >>> P0 = projection_matrix(point, normal, direct) >>> result = projection_from_matrix(P0) >>> P1 = projection_matrix(*result) >>> is_same_transform(P0, P1) True >>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=False) >>> result = projection_from_matrix(P0, pseudo=False) >>> P1 = projection_matrix(*result) >>> is_same_transform(P0, P1) True >>> P0 = projection_matrix(point, normal, perspective=persp, pseudo=True) >>> result = projection_from_matrix(P0, pseudo=True) >>> P1 = projection_matrix(*result) >>> is_same_transform(P0, P1) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=False) M33 = M[:3, :3] w, V = numpy.linalg.eig(M) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not pseudo and len(i): # point: any eigenvector corresponding to eigenvalue 1 point = numpy.real(V[:, i[-1]]).squeeze() point /= point[3] # direction: unit eigenvector corresponding to eigenvalue 0 w, V = numpy.linalg.eig(M33) i = numpy.where(abs(numpy.real(w)) < 1e-8)[0] if not len(i): raise ValueError('no eigenvector corresponding to eigenvalue 0') direction = numpy.real(V[:, i[0]]).squeeze() direction /= vector_norm(direction) # normal: unit eigenvector of M33.T corresponding to eigenvalue 0 w, V = numpy.linalg.eig(M33.T) i = numpy.where(abs(numpy.real(w)) < 1e-8)[0] if len(i): # parallel projection normal = numpy.real(V[:, i[0]]).squeeze() normal /= vector_norm(normal) return point, normal, direction, None, False else: # orthogonal projection, where normal equals direction vector return point, direction, None, None, False else: # perspective projection i = numpy.where(abs(numpy.real(w)) > 1e-8)[0] if not len(i): raise ValueError( 'no eigenvector not corresponding to eigenvalue 0') point = numpy.real(V[:, i[-1]]).squeeze() point /= point[3] normal = - M[3, :3] perspective = M[:3, 3] / numpy.dot(point[:3], normal) if pseudo: perspective -= normal return point, normal, None, perspective, pseudo def clip_matrix(left, right, bottom, top, near, far, perspective=False): """Return matrix to obtain normalized device coordinates from frustum. The frustum bounds are axis-aligned along x (left, right), y (bottom, top) and z (near, far). Normalized device coordinates are in range [-1, 1] if coordinates are inside the frustum. If perspective is True the frustum is a truncated pyramid with the perspective point at origin and direction along z axis, otherwise an orthographic canonical view volume (a box). Homogeneous coordinates transformed by the perspective clip matrix need to be dehomogenized (divided by w coordinate). >>> frustum = numpy.random.rand(6) >>> frustum[1] += frustum[0] >>> frustum[3] += frustum[2] >>> frustum[5] += frustum[4] >>> M = clip_matrix(perspective=False, *frustum) >>> numpy.dot(M, [frustum[0], frustum[2], frustum[4], 1]) array([-1., -1., -1., 1.]) >>> numpy.dot(M, [frustum[1], frustum[3], frustum[5], 1]) array([ 1., 1., 1., 1.]) >>> M = clip_matrix(perspective=True, *frustum) >>> v = numpy.dot(M, [frustum[0], frustum[2], frustum[4], 1]) >>> v / v[3] array([-1., -1., -1., 1.]) >>> v = numpy.dot(M, [frustum[1], frustum[3], frustum[4], 1]) >>> v / v[3] array([ 1., 1., -1., 1.]) """ if left >= right or bottom >= top or near >= far: raise ValueError('invalid frustum') if perspective: if near <= _EPS: raise ValueError('invalid frustum: near <= 0') t = 2.0 * near M = [[t/(left-right), 0.0, (right+left)/(right-left), 0.0], [0.0, t/(bottom-top), (top+bottom)/(top-bottom), 0.0], [0.0, 0.0, (far+near)/(near-far), t*far/(far-near)], [0.0, 0.0, -1.0, 0.0]] else: M = [[2.0/(right-left), 0.0, 0.0, (right+left)/(left-right)], [0.0, 2.0/(top-bottom), 0.0, (top+bottom)/(bottom-top)], [0.0, 0.0, 2.0/(far-near), (far+near)/(near-far)], [0.0, 0.0, 0.0, 1.0]] return numpy.array(M) def shear_matrix(angle, direction, point, normal): """Return matrix to shear by angle along direction vector on shear plane. The shear plane is defined by a point and normal vector. The direction vector must be orthogonal to the plane's normal vector. A point P is transformed by the shear matrix into P" such that the vector P-P" is parallel to the direction vector and its extent is given by the angle of P-P'-P", where P' is the orthogonal projection of P onto the shear plane. >>> angle = (random.random() - 0.5) * 4*math.pi >>> direct = numpy.random.random(3) - 0.5 >>> point = numpy.random.random(3) - 0.5 >>> normal = numpy.cross(direct, numpy.random.random(3)) >>> S = shear_matrix(angle, direct, point, normal) >>> numpy.allclose(1, numpy.linalg.det(S)) True """ normal = unit_vector(normal[:3]) direction = unit_vector(direction[:3]) if abs(numpy.dot(normal, direction)) > 1e-6: raise ValueError('direction and normal vectors are not orthogonal') angle = math.tan(angle) M = numpy.identity(4) M[:3, :3] += angle * numpy.outer(direction, normal) M[:3, 3] = -angle * numpy.dot(point[:3], normal) * direction return M def shear_from_matrix(matrix): """Return shear angle, direction and plane from shear matrix. >>> angle = (random.random() - 0.5) * 4*math.pi >>> direct = numpy.random.random(3) - 0.5 >>> point = numpy.random.random(3) - 0.5 >>> normal = numpy.cross(direct, numpy.random.random(3)) >>> S0 = shear_matrix(angle, direct, point, normal) >>> angle, direct, point, normal = shear_from_matrix(S0) >>> S1 = shear_matrix(angle, direct, point, normal) >>> is_same_transform(S0, S1) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=False) M33 = M[:3, :3] # normal: cross independent eigenvectors corresponding to the eigenvalue 1 w, V = numpy.linalg.eig(M33) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-4)[0] if len(i) < 2: raise ValueError('no two linear independent eigenvectors found %s' % w) V = numpy.real(V[:, i]).squeeze().T lenorm = -1.0 for i0, i1 in ((0, 1), (0, 2), (1, 2)): n = numpy.cross(V[i0], V[i1]) w = vector_norm(n) if w > lenorm: lenorm = w normal = n normal /= lenorm # direction and angle direction = numpy.dot(M33 - numpy.identity(3), normal) angle = vector_norm(direction) direction /= angle angle = math.atan(angle) # point: eigenvector corresponding to eigenvalue 1 w, V = numpy.linalg.eig(M) i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0] if not len(i): raise ValueError('no eigenvector corresponding to eigenvalue 1') point = numpy.real(V[:, i[-1]]).squeeze() point /= point[3] return angle, direction, point, normal def decompose_matrix(matrix): """Return sequence of transformations from transformation matrix. matrix : array_like Non-degenerative homogeneous transformation matrix Return tuple of: scale : vector of 3 scaling factors shear : list of shear factors for x-y, x-z, y-z axes angles : list of Euler angles about static x, y, z axes translate : translation vector along x, y, z axes perspective : perspective partition of matrix Raise ValueError if matrix is of wrong type or degenerative. >>> T0 = translation_matrix([1, 2, 3]) >>> scale, shear, angles, trans, persp = decompose_matrix(T0) >>> T1 = translation_matrix(trans) >>> numpy.allclose(T0, T1) True >>> S = scale_matrix(0.123) >>> scale, shear, angles, trans, persp = decompose_matrix(S) >>> scale[0] 0.123 >>> R0 = euler_matrix(1, 2, 3) >>> scale, shear, angles, trans, persp = decompose_matrix(R0) >>> R1 = euler_matrix(*angles) >>> numpy.allclose(R0, R1) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=True).T if abs(M[3, 3]) < _EPS: raise ValueError('M[3, 3] is zero') M /= M[3, 3] P = M.copy() P[:, 3] = 0.0, 0.0, 0.0, 1.0 if not numpy.linalg.det(P): raise ValueError('matrix is singular') scale = numpy.zeros((3, )) shear = [0.0, 0.0, 0.0] angles = [0.0, 0.0, 0.0] if any(abs(M[:3, 3]) > _EPS): perspective = numpy.dot(M[:, 3], numpy.linalg.inv(P.T)) M[:, 3] = 0.0, 0.0, 0.0, 1.0 else: perspective = numpy.array([0.0, 0.0, 0.0, 1.0]) translate = M[3, :3].copy() M[3, :3] = 0.0 row = M[:3, :3].copy() scale[0] = vector_norm(row[0]) row[0] /= scale[0] shear[0] = numpy.dot(row[0], row[1]) row[1] -= row[0] * shear[0] scale[1] = vector_norm(row[1]) row[1] /= scale[1] shear[0] /= scale[1] shear[1] = numpy.dot(row[0], row[2]) row[2] -= row[0] * shear[1] shear[2] = numpy.dot(row[1], row[2]) row[2] -= row[1] * shear[2] scale[2] = vector_norm(row[2]) row[2] /= scale[2] shear[1:] /= scale[2] if numpy.dot(row[0], numpy.cross(row[1], row[2])) < 0: numpy.negative(scale, scale) numpy.negative(row, row) angles[1] = math.asin(-row[0, 2]) if math.cos(angles[1]): angles[0] = math.atan2(row[1, 2], row[2, 2]) angles[2] = math.atan2(row[0, 1], row[0, 0]) else: # angles[0] = math.atan2(row[1, 0], row[1, 1]) angles[0] = math.atan2(-row[2, 1], row[1, 1]) angles[2] = 0.0 return scale, shear, angles, translate, perspective def compose_matrix(scale=None, shear=None, angles=None, translate=None, perspective=None): """Return transformation matrix from sequence of transformations. This is the inverse of the decompose_matrix function. Sequence of transformations: scale : vector of 3 scaling factors shear : list of shear factors for x-y, x-z, y-z axes angles : list of Euler angles about static x, y, z axes translate : translation vector along x, y, z axes perspective : perspective partition of matrix >>> scale = numpy.random.random(3) - 0.5 >>> shear = numpy.random.random(3) - 0.5 >>> angles = (numpy.random.random(3) - 0.5) * (2*math.pi) >>> trans = numpy.random.random(3) - 0.5 >>> persp = numpy.random.random(4) - 0.5 >>> M0 = compose_matrix(scale, shear, angles, trans, persp) >>> result = decompose_matrix(M0) >>> M1 = compose_matrix(*result) >>> is_same_transform(M0, M1) True """ M = numpy.identity(4) if perspective is not None: P = numpy.identity(4) P[3, :] = perspective[:4] M = numpy.dot(M, P) if translate is not None: T = numpy.identity(4) T[:3, 3] = translate[:3] M = numpy.dot(M, T) if angles is not None: R = euler_matrix(angles[0], angles[1], angles[2], 'sxyz') M = numpy.dot(M, R) if shear is not None: Z = numpy.identity(4) Z[1, 2] = shear[2] Z[0, 2] = shear[1] Z[0, 1] = shear[0] M = numpy.dot(M, Z) if scale is not None: S = numpy.identity(4) S[0, 0] = scale[0] S[1, 1] = scale[1] S[2, 2] = scale[2] M = numpy.dot(M, S) M /= M[3, 3] return M def orthogonalization_matrix(lengths, angles): """Return orthogonalization matrix for crystallographic cell coordinates. Angles are expected in degrees. The de-orthogonalization matrix is the inverse. >>> O = orthogonalization_matrix([10, 10, 10], [90, 90, 90]) >>> numpy.allclose(O[:3, :3], numpy.identity(3, float) * 10) True >>> O = orthogonalization_matrix([9.8, 12.0, 15.5], [87.2, 80.7, 69.7]) >>> numpy.allclose(numpy.sum(O), 43.063229) True """ a, b, c = lengths angles = numpy.radians(angles) sina, sinb, _ = numpy.sin(angles) cosa, cosb, cosg = numpy.cos(angles) co = (cosa * cosb - cosg) / (sina * sinb) return numpy.array([ [ a*sinb*math.sqrt(1.0-co*co), 0.0, 0.0, 0.0], [-a*sinb*co, b*sina, 0.0, 0.0], [ a*cosb, b*cosa, c, 0.0], [ 0.0, 0.0, 0.0, 1.0]]) def affine_matrix_from_points(v0, v1, shear=True, scale=True, usesvd=True): """Return affine transform matrix to register two point sets. v0 and v1 are shape (ndims, \*) arrays of at least ndims non-homogeneous coordinates, where ndims is the dimensionality of the coordinate space. If shear is False, a similarity transformation matrix is returned. If also scale is False, a rigid/Euclidean transformation matrix is returned. By default the algorithm by Hartley and Zissermann [15] is used. If usesvd is True, similarity and Euclidean transformation matrices are calculated by minimizing the weighted sum of squared deviations (RMSD) according to the algorithm by Kabsch [8]. Otherwise, and if ndims is 3, the quaternion based algorithm by Horn [9] is used, which is slower when using this Python implementation. The returned matrix performs rotation, translation and uniform scaling (if specified). >>> v0 = [[0, 1031, 1031, 0], [0, 0, 1600, 1600]] >>> v1 = [[675, 826, 826, 677], [55, 52, 281, 277]] >>> affine_matrix_from_points(v0, v1) array([[ 0.14549, 0.00062, 675.50008], [ 0.00048, 0.14094, 53.24971], [ 0. , 0. , 1. ]]) >>> T = translation_matrix(numpy.random.random(3)-0.5) >>> R = random_rotation_matrix(numpy.random.random(3)) >>> S = scale_matrix(random.random()) >>> M = concatenate_matrices(T, R, S) >>> v0 = (numpy.random.rand(4, 100) - 0.5) * 20 >>> v0[3] = 1 >>> v1 = numpy.dot(M, v0) >>> v0[:3] += numpy.random.normal(0, 1e-8, 300).reshape(3, -1) >>> M = affine_matrix_from_points(v0[:3], v1[:3]) >>> numpy.allclose(v1, numpy.dot(M, v0)) True More examples in superimposition_matrix() """ v0 = numpy.array(v0, dtype=numpy.float64, copy=True) v1 = numpy.array(v1, dtype=numpy.float64, copy=True) ndims = v0.shape[0] if ndims < 2 or v0.shape[1] < ndims or v0.shape != v1.shape: raise ValueError('input arrays are of wrong shape or type') # move centroids to origin t0 = -numpy.mean(v0, axis=1) M0 = numpy.identity(ndims+1) M0[:ndims, ndims] = t0 v0 += t0.reshape(ndims, 1) t1 = -numpy.mean(v1, axis=1) M1 = numpy.identity(ndims+1) M1[:ndims, ndims] = t1 v1 += t1.reshape(ndims, 1) if shear: # Affine transformation A = numpy.concatenate((v0, v1), axis=0) u, s, vh = numpy.linalg.svd(A.T) vh = vh[:ndims].T B = vh[:ndims] C = vh[ndims:2*ndims] t = numpy.dot(C, numpy.linalg.pinv(B)) t = numpy.concatenate((t, numpy.zeros((ndims, 1))), axis=1) M = numpy.vstack((t, ((0.0,)*ndims) + (1.0,))) elif usesvd or ndims != 3: # Rigid transformation via SVD of covariance matrix u, s, vh = numpy.linalg.svd(numpy.dot(v1, v0.T)) # rotation matrix from SVD orthonormal bases R = numpy.dot(u, vh) if numpy.linalg.det(R) < 0.0: # R does not constitute right handed system R -= numpy.outer(u[:, ndims-1], vh[ndims-1, :]*2.0) s[-1] *= -1.0 # homogeneous transformation matrix M = numpy.identity(ndims+1) M[:ndims, :ndims] = R else: # Rigid transformation matrix via quaternion # compute symmetric matrix N xx, yy, zz = numpy.sum(v0 * v1, axis=1) xy, yz, zx = numpy.sum(v0 * numpy.roll(v1, -1, axis=0), axis=1) xz, yx, zy = numpy.sum(v0 * numpy.roll(v1, -2, axis=0), axis=1) N = [[xx+yy+zz, 0.0, 0.0, 0.0], [yz-zy, xx-yy-zz, 0.0, 0.0], [zx-xz, xy+yx, yy-xx-zz, 0.0], [xy-yx, zx+xz, yz+zy, zz-xx-yy]] # quaternion: eigenvector corresponding to most positive eigenvalue w, V = numpy.linalg.eigh(N) q = V[:, numpy.argmax(w)] q /= vector_norm(q) # unit quaternion # homogeneous transformation matrix M = quaternion_matrix(q) if scale and not shear: # Affine transformation; scale is ratio of RMS deviations from centroid v0 *= v0 v1 *= v1 M[:ndims, :ndims] *= math.sqrt(numpy.sum(v1) / numpy.sum(v0)) # move centroids back M = numpy.dot(numpy.linalg.inv(M1), numpy.dot(M, M0)) M /= M[ndims, ndims] return M def superimposition_matrix(v0, v1, scale=False, usesvd=True): """Return matrix to transform given 3D point set into second point set. v0 and v1 are shape (3, \*) or (4, \*) arrays of at least 3 points. The parameters scale and usesvd are explained in the more general affine_matrix_from_points function. The returned matrix is a similarity or Euclidean transformation matrix. This function has a fast C implementation in transformations.c. >>> v0 = numpy.random.rand(3, 10) >>> M = superimposition_matrix(v0, v0) >>> numpy.allclose(M, numpy.identity(4)) True >>> R = random_rotation_matrix(numpy.random.random(3)) >>> v0 = [[1,0,0], [0,1,0], [0,0,1], [1,1,1]] >>> v1 = numpy.dot(R, v0) >>> M = superimposition_matrix(v0, v1) >>> numpy.allclose(v1, numpy.dot(M, v0)) True >>> v0 = (numpy.random.rand(4, 100) - 0.5) * 20 >>> v0[3] = 1 >>> v1 = numpy.dot(R, v0) >>> M = superimposition_matrix(v0, v1) >>> numpy.allclose(v1, numpy.dot(M, v0)) True >>> S = scale_matrix(random.random()) >>> T = translation_matrix(numpy.random.random(3)-0.5) >>> M = concatenate_matrices(T, R, S) >>> v1 = numpy.dot(M, v0) >>> v0[:3] += numpy.random.normal(0, 1e-9, 300).reshape(3, -1) >>> M = superimposition_matrix(v0, v1, scale=True) >>> numpy.allclose(v1, numpy.dot(M, v0)) True >>> M = superimposition_matrix(v0, v1, scale=True, usesvd=False) >>> numpy.allclose(v1, numpy.dot(M, v0)) True >>> v = numpy.empty((4, 100, 3)) >>> v[:, :, 0] = v0 >>> M = superimposition_matrix(v0, v1, scale=True, usesvd=False) >>> numpy.allclose(v1, numpy.dot(M, v[:, :, 0])) True """ v0 = numpy.array(v0, dtype=numpy.float64, copy=False)[:3] v1 = numpy.array(v1, dtype=numpy.float64, copy=False)[:3] return affine_matrix_from_points(v0, v1, shear=False, scale=scale, usesvd=usesvd) def euler_matrix(ai, aj, ak, axes='sxyz'): """Return homogeneous rotation matrix from Euler angles and axis sequence. ai, aj, ak : Euler's roll, pitch and yaw angles axes : One of 24 axis sequences as string or encoded tuple >>> R = euler_matrix(1, 2, 3, 'syxz') >>> numpy.allclose(numpy.sum(R[0]), -1.34786452) True >>> R = euler_matrix(1, 2, 3, (0, 1, 0, 1)) >>> numpy.allclose(numpy.sum(R[0]), -0.383436184) True >>> ai, aj, ak = (4*math.pi) * (numpy.random.random(3) - 0.5) >>> for axes in _AXES2TUPLE.keys(): ... R = euler_matrix(ai, aj, ak, axes) >>> for axes in _TUPLE2AXES.keys(): ... R = euler_matrix(ai, aj, ak, axes) """ try: firstaxis, parity, repetition, frame = _AXES2TUPLE[axes] except (AttributeError, KeyError): _TUPLE2AXES[axes] # validation firstaxis, parity, repetition, frame = axes i = firstaxis j = _NEXT_AXIS[i+parity] k = _NEXT_AXIS[i-parity+1] if frame: ai, ak = ak, ai if parity: ai, aj, ak = -ai, -aj, -ak si, sj, sk = math.sin(ai), math.sin(aj), math.sin(ak) ci, cj, ck = math.cos(ai), math.cos(aj), math.cos(ak) cc, cs = ci*ck, ci*sk sc, ss = si*ck, si*sk M = numpy.identity(4) if repetition: M[i, i] = cj M[i, j] = sj*si M[i, k] = sj*ci M[j, i] = sj*sk M[j, j] = -cj*ss+cc M[j, k] = -cj*cs-sc M[k, i] = -sj*ck M[k, j] = cj*sc+cs M[k, k] = cj*cc-ss else: M[i, i] = cj*ck M[i, j] = sj*sc-cs M[i, k] = sj*cc+ss M[j, i] = cj*sk M[j, j] = sj*ss+cc M[j, k] = sj*cs-sc M[k, i] = -sj M[k, j] = cj*si M[k, k] = cj*ci return M def euler_from_matrix(matrix, axes='sxyz'): """Return Euler angles from rotation matrix for specified axis sequence. axes : One of 24 axis sequences as string or encoded tuple Note that many Euler angle triplets can describe one matrix. >>> R0 = euler_matrix(1, 2, 3, 'syxz') >>> al, be, ga = euler_from_matrix(R0, 'syxz') >>> R1 = euler_matrix(al, be, ga, 'syxz') >>> numpy.allclose(R0, R1) True >>> angles = (4*math.pi) * (numpy.random.random(3) - 0.5) >>> for axes in _AXES2TUPLE.keys(): ... R0 = euler_matrix(axes=axes, *angles) ... R1 = euler_matrix(axes=axes, *euler_from_matrix(R0, axes)) ... if not numpy.allclose(R0, R1): print(axes, "failed") """ try: firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] except (AttributeError, KeyError): _TUPLE2AXES[axes] # validation firstaxis, parity, repetition, frame = axes i = firstaxis j = _NEXT_AXIS[i+parity] k = _NEXT_AXIS[i-parity+1] M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:3, :3] if repetition: sy = math.sqrt(M[i, j]*M[i, j] + M[i, k]*M[i, k]) if sy > _EPS: ax = math.atan2( M[i, j], M[i, k]) ay = math.atan2( sy, M[i, i]) az = math.atan2( M[j, i], -M[k, i]) else: ax = math.atan2(-M[j, k], M[j, j]) ay = math.atan2( sy, M[i, i]) az = 0.0 else: cy = math.sqrt(M[i, i]*M[i, i] + M[j, i]*M[j, i]) if cy > _EPS: ax = math.atan2( M[k, j], M[k, k]) ay = math.atan2(-M[k, i], cy) az = math.atan2( M[j, i], M[i, i]) else: ax = math.atan2(-M[j, k], M[j, j]) ay = math.atan2(-M[k, i], cy) az = 0.0 if parity: ax, ay, az = -ax, -ay, -az if frame: ax, az = az, ax return ax, ay, az def euler_from_quaternion(quaternion, axes='sxyz'): """Return Euler angles from quaternion for specified axis sequence. >>> angles = euler_from_quaternion([0.99810947, 0.06146124, 0, 0]) >>> numpy.allclose(angles, [0.123, 0, 0]) True """ return euler_from_matrix(quaternion_matrix(quaternion), axes) def quaternion_from_euler(ai, aj, ak, axes='sxyz'): """Return quaternion from Euler angles and axis sequence. ai, aj, ak : Euler's roll, pitch and yaw angles axes : One of 24 axis sequences as string or encoded tuple >>> q = quaternion_from_euler(1, 2, 3, 'ryxz') >>> numpy.allclose(q, [0.435953, 0.310622, -0.718287, 0.444435]) True """ try: firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()] except (AttributeError, KeyError): _TUPLE2AXES[axes] # validation firstaxis, parity, repetition, frame = axes i = firstaxis + 1 j = _NEXT_AXIS[i+parity-1] + 1 k = _NEXT_AXIS[i-parity] + 1 if frame: ai, ak = ak, ai if parity: aj = -aj ai /= 2.0 aj /= 2.0 ak /= 2.0 ci = math.cos(ai) si = math.sin(ai) cj = math.cos(aj) sj = math.sin(aj) ck = math.cos(ak) sk = math.sin(ak) cc = ci*ck cs = ci*sk sc = si*ck ss = si*sk q = numpy.empty((4, )) if repetition: q[0] = cj*(cc - ss) q[i] = cj*(cs + sc) q[j] = sj*(cc + ss) q[k] = sj*(cs - sc) else: q[0] = cj*cc + sj*ss q[i] = cj*sc - sj*cs q[j] = cj*ss + sj*cc q[k] = cj*cs - sj*sc if parity: q[j] *= -1.0 return q def quaternion_about_axis(angle, axis): """Return quaternion for rotation about axis. >>> q = quaternion_about_axis(0.123, [1, 0, 0]) >>> numpy.allclose(q, [0.99810947, 0.06146124, 0, 0]) True """ q = numpy.array([0.0, axis[0], axis[1], axis[2]]) qlen = vector_norm(q) if qlen > _EPS: q *= math.sin(angle/2.0) / qlen q[0] = math.cos(angle/2.0) return q def quaternion_matrix(quaternion): """Return homogeneous rotation matrix from quaternion. >>> M = quaternion_matrix([0.99810947, 0.06146124, 0, 0]) >>> numpy.allclose(M, rotation_matrix(0.123, [1, 0, 0])) True >>> M = quaternion_matrix([1, 0, 0, 0]) >>> numpy.allclose(M, numpy.identity(4)) True >>> M = quaternion_matrix([0, 1, 0, 0]) >>> numpy.allclose(M, numpy.diag([1, -1, -1, 1])) True """ q = numpy.array(quaternion, dtype=numpy.float64, copy=True) n = numpy.dot(q, q) if n < _EPS: return numpy.identity(4) q *= math.sqrt(2.0 / n) q = numpy.outer(q, q) return numpy.array([ [1.0-q[2, 2]-q[3, 3], q[1, 2]-q[3, 0], q[1, 3]+q[2, 0], 0.0], [ q[1, 2]+q[3, 0], 1.0-q[1, 1]-q[3, 3], q[2, 3]-q[1, 0], 0.0], [ q[1, 3]-q[2, 0], q[2, 3]+q[1, 0], 1.0-q[1, 1]-q[2, 2], 0.0], [ 0.0, 0.0, 0.0, 1.0]]) def quaternion_from_matrix(matrix, isprecise=False): """Return quaternion from rotation matrix. If isprecise is True, the input matrix is assumed to be a precise rotation matrix and a faster algorithm is used. >>> q = quaternion_from_matrix(numpy.identity(4), True) >>> numpy.allclose(q, [1, 0, 0, 0]) True >>> q = quaternion_from_matrix(numpy.diag([1, -1, -1, 1])) >>> numpy.allclose(q, [0, 1, 0, 0]) or numpy.allclose(q, [0, -1, 0, 0]) True >>> R = rotation_matrix(0.123, (1, 2, 3)) >>> q = quaternion_from_matrix(R, True) >>> numpy.allclose(q, [0.9981095, 0.0164262, 0.0328524, 0.0492786]) True >>> R = [[-0.545, 0.797, 0.260, 0], [0.733, 0.603, -0.313, 0], ... [-0.407, 0.021, -0.913, 0], [0, 0, 0, 1]] >>> q = quaternion_from_matrix(R) >>> numpy.allclose(q, [0.19069, 0.43736, 0.87485, -0.083611]) True >>> R = [[0.395, 0.362, 0.843, 0], [-0.626, 0.796, -0.056, 0], ... [-0.677, -0.498, 0.529, 0], [0, 0, 0, 1]] >>> q = quaternion_from_matrix(R) >>> numpy.allclose(q, [0.82336615, -0.13610694, 0.46344705, -0.29792603]) True >>> R = random_rotation_matrix() >>> q = quaternion_from_matrix(R) >>> is_same_transform(R, quaternion_matrix(q)) True >>> is_same_quaternion(quaternion_from_matrix(R, isprecise=False), ... quaternion_from_matrix(R, isprecise=True)) True >>> R = euler_matrix(0.0, 0.0, numpy.pi/2.0) >>> is_same_quaternion(quaternion_from_matrix(R, isprecise=False), ... quaternion_from_matrix(R, isprecise=True)) True """ M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:4, :4] if isprecise: q = numpy.empty((4, )) t = numpy.trace(M) if t > M[3, 3]: q[0] = t q[3] = M[1, 0] - M[0, 1] q[2] = M[0, 2] - M[2, 0] q[1] = M[2, 1] - M[1, 2] else: i, j, k = 0, 1, 2 if M[1, 1] > M[0, 0]: i, j, k = 1, 2, 0 if M[2, 2] > M[i, i]: i, j, k = 2, 0, 1 t = M[i, i] - (M[j, j] + M[k, k]) + M[3, 3] q[i] = t q[j] = M[i, j] + M[j, i] q[k] = M[k, i] + M[i, k] q[3] = M[k, j] - M[j, k] q = q[[3, 0, 1, 2]] q *= 0.5 / math.sqrt(t * M[3, 3]) else: m00 = M[0, 0] m01 = M[0, 1] m02 = M[0, 2] m10 = M[1, 0] m11 = M[1, 1] m12 = M[1, 2] m20 = M[2, 0] m21 = M[2, 1] m22 = M[2, 2] # symmetric matrix K K = numpy.array([[m00-m11-m22, 0.0, 0.0, 0.0], [m01+m10, m11-m00-m22, 0.0, 0.0], [m02+m20, m12+m21, m22-m00-m11, 0.0], [m21-m12, m02-m20, m10-m01, m00+m11+m22]]) K /= 3.0 # quaternion is eigenvector of K that corresponds to largest eigenvalue w, V = numpy.linalg.eigh(K) q = V[[3, 0, 1, 2], numpy.argmax(w)] if q[0] < 0.0: numpy.negative(q, q) return q def quaternion_multiply(quaternion1, quaternion0): """Return multiplication of two quaternions. >>> q = quaternion_multiply([4, 1, -2, 3], [8, -5, 6, 7]) >>> numpy.allclose(q, [28, -44, -14, 48]) True """ w0, x0, y0, z0 = quaternion0 w1, x1, y1, z1 = quaternion1 return numpy.array([ -x1*x0 - y1*y0 - z1*z0 + w1*w0, x1*w0 + y1*z0 - z1*y0 + w1*x0, -x1*z0 + y1*w0 + z1*x0 + w1*y0, x1*y0 - y1*x0 + z1*w0 + w1*z0], dtype=numpy.float64) def quaternion_conjugate(quaternion): """Return conjugate of quaternion. >>> q0 = random_quaternion() >>> q1 = quaternion_conjugate(q0) >>> q1[0] == q0[0] and all(q1[1:] == -q0[1:]) True """ q = numpy.array(quaternion, dtype=numpy.float64, copy=True) numpy.negative(q[1:], q[1:]) return q def quaternion_inverse(quaternion): """Return inverse of quaternion. >>> q0 = random_quaternion() >>> q1 = quaternion_inverse(q0) >>> numpy.allclose(quaternion_multiply(q0, q1), [1, 0, 0, 0]) True """ q = numpy.array(quaternion, dtype=numpy.float64, copy=True) numpy.negative(q[1:], q[1:]) return q / numpy.dot(q, q) def quaternion_real(quaternion): """Return real part of quaternion. >>> quaternion_real([3, 0, 1, 2]) 3.0 """ return float(quaternion[0]) def quaternion_imag(quaternion): """Return imaginary part of quaternion. >>> quaternion_imag([3, 0, 1, 2]) array([ 0., 1., 2.]) """ return numpy.array(quaternion[1:4], dtype=numpy.float64, copy=True) def quaternion_slerp(quat0, quat1, fraction, spin=0, shortestpath=True): """Return spherical linear interpolation between two quaternions. >>> q0 = random_quaternion() >>> q1 = random_quaternion() >>> q = quaternion_slerp(q0, q1, 0) >>> numpy.allclose(q, q0) True >>> q = quaternion_slerp(q0, q1, 1, 1) >>> numpy.allclose(q, q1) True >>> q = quaternion_slerp(q0, q1, 0.5) >>> angle = math.acos(numpy.dot(q0, q)) >>> numpy.allclose(2, math.acos(numpy.dot(q0, q1)) / angle) or \ numpy.allclose(2, math.acos(-numpy.dot(q0, q1)) / angle) True """ q0 = unit_vector(quat0[:4]) q1 = unit_vector(quat1[:4]) if fraction == 0.0: return q0 elif fraction == 1.0: return q1 d = numpy.dot(q0, q1) if abs(abs(d) - 1.0) < _EPS: return q0 if shortestpath and d < 0.0: # invert rotation d = -d numpy.negative(q1, q1) angle = math.acos(d) + spin * math.pi if abs(angle) < _EPS: return q0 isin = 1.0 / math.sin(angle) q0 *= math.sin((1.0 - fraction) * angle) * isin q1 *= math.sin(fraction * angle) * isin q0 += q1 return q0 def random_quaternion(rand=None): """Return uniform random unit quaternion. rand: array like or None Three independent random variables that are uniformly distributed between 0 and 1. >>> q = random_quaternion() >>> numpy.allclose(1, vector_norm(q)) True >>> q = random_quaternion(numpy.random.random(3)) >>> len(q.shape), q.shape[0]==4 (1, True) """ if rand is None: rand = numpy.random.rand(3) else: assert len(rand) == 3 r1 = numpy.sqrt(1.0 - rand[0]) r2 = numpy.sqrt(rand[0]) pi2 = math.pi * 2.0 t1 = pi2 * rand[1] t2 = pi2 * rand[2] return numpy.array([numpy.cos(t2)*r2, numpy.sin(t1)*r1, numpy.cos(t1)*r1, numpy.sin(t2)*r2]) def random_rotation_matrix(rand=None): """Return uniform random rotation matrix. rand: array like Three independent random variables that are uniformly distributed between 0 and 1 for each returned quaternion. >>> R = random_rotation_matrix() >>> numpy.allclose(numpy.dot(R.T, R), numpy.identity(4)) True """ return quaternion_matrix(random_quaternion(rand)) class Arcball(object): """Virtual Trackball Control. >>> ball = Arcball() >>> ball = Arcball(initial=numpy.identity(4)) >>> ball.place([320, 320], 320) >>> ball.down([500, 250]) >>> ball.drag([475, 275]) >>> R = ball.matrix() >>> numpy.allclose(numpy.sum(R), 3.90583455) True >>> ball = Arcball(initial=[1, 0, 0, 0]) >>> ball.place([320, 320], 320) >>> ball.setaxes([1, 1, 0], [-1, 1, 0]) >>> ball.constrain = True >>> ball.down([400, 200]) >>> ball.drag([200, 400]) >>> R = ball.matrix() >>> numpy.allclose(numpy.sum(R), 0.2055924) True >>> ball.next() """ def __init__(self, initial=None): """Initialize virtual trackball control. initial : quaternion or rotation matrix """ self._axis = None self._axes = None self._radius = 1.0 self._center = [0.0, 0.0] self._vdown = numpy.array([0.0, 0.0, 1.0]) self._constrain = False if initial is None: self._qdown = numpy.array([1.0, 0.0, 0.0, 0.0]) else: initial = numpy.array(initial, dtype=numpy.float64) if initial.shape == (4, 4): self._qdown = quaternion_from_matrix(initial) elif initial.shape == (4, ): initial /= vector_norm(initial) self._qdown = initial else: raise ValueError("initial not a quaternion or matrix") self._qnow = self._qpre = self._qdown def place(self, center, radius): """Place Arcball, e.g. when window size changes. center : sequence[2] Window coordinates of trackball center. radius : float Radius of trackball in window coordinates. """ self._radius = float(radius) self._center[0] = center[0] self._center[1] = center[1] def setaxes(self, *axes): """Set axes to constrain rotations.""" if axes is None: self._axes = None else: self._axes = [unit_vector(axis) for axis in axes] @property def constrain(self): """Return state of constrain to axis mode.""" return self._constrain @constrain.setter def constrain(self, value): """Set state of constrain to axis mode.""" self._constrain = bool(value) def down(self, point): """Set initial cursor window coordinates and pick constrain-axis.""" self._vdown = arcball_map_to_sphere(point, self._center, self._radius) self._qdown = self._qpre = self._qnow if self._constrain and self._axes is not None: self._axis = arcball_nearest_axis(self._vdown, self._axes) self._vdown = arcball_constrain_to_axis(self._vdown, self._axis) else: self._axis = None def drag(self, point): """Update current cursor window coordinates.""" vnow = arcball_map_to_sphere(point, self._center, self._radius) if self._axis is not None: vnow = arcball_constrain_to_axis(vnow, self._axis) self._qpre = self._qnow t = numpy.cross(self._vdown, vnow) if numpy.dot(t, t) < _EPS: self._qnow = self._qdown else: q = [numpy.dot(self._vdown, vnow), t[0], t[1], t[2]] self._qnow = quaternion_multiply(q, self._qdown) def next(self, acceleration=0.0): """Continue rotation in direction of last drag.""" q = quaternion_slerp(self._qpre, self._qnow, 2.0+acceleration, False) self._qpre, self._qnow = self._qnow, q def matrix(self): """Return homogeneous rotation matrix.""" return quaternion_matrix(self._qnow) def arcball_map_to_sphere(point, center, radius): """Return unit sphere coordinates from window coordinates.""" v0 = (point[0] - center[0]) / radius v1 = (center[1] - point[1]) / radius n = v0*v0 + v1*v1 if n > 1.0: # position outside of sphere n = math.sqrt(n) return numpy.array([v0/n, v1/n, 0.0]) else: return numpy.array([v0, v1, math.sqrt(1.0 - n)]) def arcball_constrain_to_axis(point, axis): """Return sphere point perpendicular to axis.""" v = numpy.array(point, dtype=numpy.float64, copy=True) a = numpy.array(axis, dtype=numpy.float64, copy=True) v -= a * numpy.dot(a, v) # on plane n = vector_norm(v) if n > _EPS: if v[2] < 0.0: numpy.negative(v, v) v /= n return v if a[2] == 1.0: return numpy.array([1.0, 0.0, 0.0]) return unit_vector([-a[1], a[0], 0.0]) def arcball_nearest_axis(point, axes): """Return axis, which arc is nearest to point.""" point = numpy.array(point, dtype=numpy.float64, copy=False) nearest = None mx = -1.0 for axis in axes: t = numpy.dot(arcball_constrain_to_axis(point, axis), point) if t > mx: nearest = axis mx = t return nearest # epsilon for testing whether a number is close to zero _EPS = numpy.finfo(float).eps * 4.0 # axis sequences for Euler angles _NEXT_AXIS = [1, 2, 0, 1] # map axes strings to/from tuples of inner axis, parity, repetition, frame _AXES2TUPLE = { 'sxyz': (0, 0, 0, 0), 'sxyx': (0, 0, 1, 0), 'sxzy': (0, 1, 0, 0), 'sxzx': (0, 1, 1, 0), 'syzx': (1, 0, 0, 0), 'syzy': (1, 0, 1, 0), 'syxz': (1, 1, 0, 0), 'syxy': (1, 1, 1, 0), 'szxy': (2, 0, 0, 0), 'szxz': (2, 0, 1, 0), 'szyx': (2, 1, 0, 0), 'szyz': (2, 1, 1, 0), 'rzyx': (0, 0, 0, 1), 'rxyx': (0, 0, 1, 1), 'ryzx': (0, 1, 0, 1), 'rxzx': (0, 1, 1, 1), 'rxzy': (1, 0, 0, 1), 'ryzy': (1, 0, 1, 1), 'rzxy': (1, 1, 0, 1), 'ryxy': (1, 1, 1, 1), 'ryxz': (2, 0, 0, 1), 'rzxz': (2, 0, 1, 1), 'rxyz': (2, 1, 0, 1), 'rzyz': (2, 1, 1, 1)} _TUPLE2AXES = dict((v, k) for k, v in _AXES2TUPLE.items()) def vector_norm(data, axis=None, out=None): """Return length, i.e. Euclidean norm, of ndarray along axis. >>> v = numpy.random.random(3) >>> n = vector_norm(v) >>> numpy.allclose(n, numpy.linalg.norm(v)) True >>> v = numpy.random.rand(6, 5, 3) >>> n = vector_norm(v, axis=-1) >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=2))) True >>> n = vector_norm(v, axis=1) >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1))) True >>> v = numpy.random.rand(5, 4, 3) >>> n = numpy.empty((5, 3)) >>> vector_norm(v, axis=1, out=n) >>> numpy.allclose(n, numpy.sqrt(numpy.sum(v*v, axis=1))) True >>> vector_norm([]) 0.0 >>> vector_norm([1]) 1.0 """ data = numpy.array(data, dtype=numpy.float64, copy=True) if out is None: if data.ndim == 1: return math.sqrt(numpy.dot(data, data)) data *= data out = numpy.atleast_1d(numpy.sum(data, axis=axis)) numpy.sqrt(out, out) return out else: data *= data numpy.sum(data, axis=axis, out=out) numpy.sqrt(out, out) def unit_vector(data, axis=None, out=None): """Return ndarray normalized by length, i.e. Euclidean norm, along axis. >>> v0 = numpy.random.random(3) >>> v1 = unit_vector(v0) >>> numpy.allclose(v1, v0 / numpy.linalg.norm(v0)) True >>> v0 = numpy.random.rand(5, 4, 3) >>> v1 = unit_vector(v0, axis=-1) >>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=2)), 2) >>> numpy.allclose(v1, v2) True >>> v1 = unit_vector(v0, axis=1) >>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=1)), 1) >>> numpy.allclose(v1, v2) True >>> v1 = numpy.empty((5, 4, 3)) >>> unit_vector(v0, axis=1, out=v1) >>> numpy.allclose(v1, v2) True >>> list(unit_vector([])) [] >>> list(unit_vector([1])) [1.0] """ if out is None: data = numpy.array(data, dtype=numpy.float64, copy=True) if data.ndim == 1: data /= math.sqrt(numpy.dot(data, data)) return data else: if out is not data: out[:] = numpy.array(data, copy=False) data = out length = numpy.atleast_1d(numpy.sum(data*data, axis)) numpy.sqrt(length, length) if axis is not None: length = numpy.expand_dims(length, axis) data /= length if out is None: return data def random_vector(size): """Return array of random doubles in the half-open interval [0.0, 1.0). >>> v = random_vector(10000) >>> numpy.all(v >= 0) and numpy.all(v < 1) True >>> v0 = random_vector(10) >>> v1 = random_vector(10) >>> numpy.any(v0 == v1) False """ return numpy.random.random(size) def vector_product(v0, v1, axis=0): """Return vector perpendicular to vectors. >>> v = vector_product([2, 0, 0], [0, 3, 0]) >>> numpy.allclose(v, [0, 0, 6]) True >>> v0 = [[2, 0, 0, 2], [0, 2, 0, 2], [0, 0, 2, 2]] >>> v1 = [[3], [0], [0]] >>> v = vector_product(v0, v1) >>> numpy.allclose(v, [[0, 0, 0, 0], [0, 0, 6, 6], [0, -6, 0, -6]]) True >>> v0 = [[2, 0, 0], [2, 0, 0], [0, 2, 0], [2, 0, 0]] >>> v1 = [[0, 3, 0], [0, 0, 3], [0, 0, 3], [3, 3, 3]] >>> v = vector_product(v0, v1, axis=1) >>> numpy.allclose(v, [[0, 0, 6], [0, -6, 0], [6, 0, 0], [0, -6, 6]]) True """ return numpy.cross(v0, v1, axis=axis) def angle_between_vectors(v0, v1, directed=True, axis=0): """Return angle between vectors. If directed is False, the input vectors are interpreted as undirected axes, i.e. the maximum angle is pi/2. >>> a = angle_between_vectors([1, -2, 3], [-1, 2, -3]) >>> numpy.allclose(a, math.pi) True >>> a = angle_between_vectors([1, -2, 3], [-1, 2, -3], directed=False) >>> numpy.allclose(a, 0) True >>> v0 = [[2, 0, 0, 2], [0, 2, 0, 2], [0, 0, 2, 2]] >>> v1 = [[3], [0], [0]] >>> a = angle_between_vectors(v0, v1) >>> numpy.allclose(a, [0, 1.5708, 1.5708, 0.95532]) True >>> v0 = [[2, 0, 0], [2, 0, 0], [0, 2, 0], [2, 0, 0]] >>> v1 = [[0, 3, 0], [0, 0, 3], [0, 0, 3], [3, 3, 3]] >>> a = angle_between_vectors(v0, v1, axis=1) >>> numpy.allclose(a, [1.5708, 1.5708, 1.5708, 0.95532]) True """ v0 = numpy.array(v0, dtype=numpy.float64, copy=False) v1 = numpy.array(v1, dtype=numpy.float64, copy=False) dot = numpy.sum(v0 * v1, axis=axis) dot /= vector_norm(v0, axis=axis) * vector_norm(v1, axis=axis) dot = numpy.clip(dot, -1.0, 1.0) return numpy.arccos(dot if directed else numpy.fabs(dot)) def inverse_matrix(matrix): """Return inverse of square transformation matrix. >>> M0 = random_rotation_matrix() >>> M1 = inverse_matrix(M0.T) >>> numpy.allclose(M1, numpy.linalg.inv(M0.T)) True >>> for size in range(1, 7): ... M0 = numpy.random.rand(size, size) ... M1 = inverse_matrix(M0) ... if not numpy.allclose(M1, numpy.linalg.inv(M0)): print(size) """ return numpy.linalg.inv(matrix) def concatenate_matrices(*matrices): """Return concatenation of series of transformation matrices. >>> M = numpy.random.rand(16).reshape((4, 4)) - 0.5 >>> numpy.allclose(M, concatenate_matrices(M)) True >>> numpy.allclose(numpy.dot(M, M.T), concatenate_matrices(M, M.T)) True """ M = numpy.identity(4) for i in matrices: M = numpy.dot(M, i) return M def is_same_transform(matrix0, matrix1): """Return True if two matrices perform same transformation. >>> is_same_transform(numpy.identity(4), numpy.identity(4)) True >>> is_same_transform(numpy.identity(4), random_rotation_matrix()) False """ matrix0 = numpy.array(matrix0, dtype=numpy.float64, copy=True) matrix0 /= matrix0[3, 3] matrix1 = numpy.array(matrix1, dtype=numpy.float64, copy=True) matrix1 /= matrix1[3, 3] return numpy.allclose(matrix0, matrix1) def is_same_quaternion(q0, q1): """Return True if two quaternions are equal.""" q0 = numpy.array(q0) q1 = numpy.array(q1) return numpy.allclose(q0, q1) or numpy.allclose(q0, -q1) def _import_module(name, package=None, warn=True, prefix='_py_', ignore='_'): """Try import all public attributes from module into global namespace. Existing attributes with name clashes are renamed with prefix. Attributes starting with underscore are ignored by default. Return True on successful import. """ import warnings from importlib import import_module try: if not package: module = import_module(name) else: module = import_module('.' + name, package=package) except ImportError: if warn: warnings.warn('failed to import module %s' % name) else: for attr in dir(module): if ignore and attr.startswith(ignore): continue if prefix: if attr in globals(): globals()[prefix + attr] = globals()[attr] elif warn: warnings.warn('no Python implementation of ' + attr) globals()[attr] = getattr(module, attr) return True _import_module('_transformations') if __name__ == '__main__': import doctest import random # noqa: used in doctests try: numpy.set_printoptions(suppress=True, precision=5, legacy='1.13') except TypeError: numpy.set_printoptions(suppress=True, precision=5) doctest.testmod() ================================================ FILE: DenseFusion/lib/utils.py ================================================ import logging def setup_logger(logger_name, log_file, level=logging.INFO): l = logging.getLogger(logger_name) formatter = logging.Formatter('%(asctime)s : %(message)s') fileHandler = logging.FileHandler(log_file, mode='w') fileHandler.setFormatter(formatter) l.setLevel(level) l.addHandler(fileHandler) streamHandler = logging.StreamHandler() streamHandler.setFormatter(formatter) l.addHandler(streamHandler) return l ================================================ FILE: DenseFusion/note.txt ================================================ git checkout branch Pytorch-1.0 # Error: AttributeError: module 'lib.knn.knn_pytorch' has no attribute 'knn' Solution: rebuild and unzip egg ile then copy *so file and knn_pytorch.py to /densefusion/lib/knn root@cfde89f97b76:/densefusion/lib/knn# python setup.py install root@cfde89f97b76:/densefusion/lib/knn/dist# unzip knn_pytorch-0.1-py3.5-linux-x86_64.egg ================================================ FILE: DenseFusion/tools/_init_paths.py ================================================ import os import sys sys.path.insert(0, os.getcwd()) ================================================ FILE: DenseFusion/tools/iliad.py ================================================ import _init_paths import argparse import os import copy import random import numpy as np from PIL import Image import scipy.io as scio import scipy.misc import numpy.ma as ma import math import torch import torch.nn as nn import torch.nn.parallel import torch.backends.cudnn as cudnn import torch.optim as optim import torch.utils.data import torchvision.datasets as dset import torchvision.transforms as transforms import torchvision.utils as vutils import torch.nn.functional as F from torch.autograd import Variable from lib.network import PoseNet, PoseRefineNet from lib.transformations import euler_matrix, quaternion_matrix, quaternion_from_matrix import matplotlib.pyplot as plt parser = argparse.ArgumentParser() parser.add_argument('--dataset_root', type=str, default = '', help='dataset root dir') parser.add_argument('--saved_root', type=str, default = '', help='saved result root dir') parser.add_argument('--model', type=str, default = '', help='resume PoseNet model') parser.add_argument('--refine_model', type=str, default = '', help='resume PoseRefineNet model') parser.add_argument('--num_frames', type=int, default = 100, help='number of frames') parser.add_argument('--num_keyframes', type=int, default = 10, help='number of frames') opt = parser.parse_args() norm = transforms.Normalize(mean=[0.485, 0.456, 0.406], std=[0.229, 0.224, 0.225]) border_list = [-1, 40, 80, 120, 160, 200, 240, 280, 320, 360, 400, 440, 480, 520, 560, 600, 640, 680] xmap = np.array([[j for i in range(640)] for j in range(480)]) ymap = np.array([[i for i in range(640)] for j in range(480)]) cam_cx = 319.0000 cam_cy = 237.0000 cam_fx = 580.000 cam_fy = 580.000 cam_scale = 1000.0 num_obj = 13 img_width = 480 img_length = 640 num_points = 1000 num_points_mesh = 500 iteration = 2 bs = 1 dataset_config_dir = opt.dataset_root + '/image_sets' def get_bbox(label): rows = np.any(label, axis=1) cols = np.any(label, axis=0) rmin, rmax = np.where(rows)[0][[0, -1]] cmin, cmax = np.where(cols)[0][[0, -1]] rmax += 1 cmax += 1 r_b = rmax - rmin for tt in range(len(border_list)): if r_b > border_list[tt] and r_b < border_list[tt + 1]: r_b = border_list[tt + 1] break c_b = cmax - cmin for tt in range(len(border_list)): if c_b > border_list[tt] and c_b < border_list[tt + 1]: c_b = border_list[tt + 1] break center = [int((rmin + rmax) / 2), int((cmin + cmax) / 2)] rmin = center[0] - int(r_b / 2) rmax = center[0] + int(r_b / 2) cmin = center[1] - int(c_b / 2) cmax = center[1] + int(c_b / 2) if rmin < 0: delt = -rmin rmin = 0 rmax += delt if cmin < 0: delt = -cmin cmin = 0 cmax += delt if rmax > img_width: delt = rmax - img_width rmax = img_width rmin -= delt if cmax > img_length: delt = cmax - img_length cmax = img_length cmin -= delt return rmin, rmax, cmin, cmax estimator = PoseNet(num_points = num_points, num_obj = num_obj) estimator.cuda() estimator.load_state_dict(torch.load(opt.model)) estimator.eval() refiner = PoseRefineNet(num_points = num_points, num_obj = num_obj) refiner.cuda() refiner.load_state_dict(torch.load(opt.refine_model)) refiner.eval() class_file = open('{0}/classes.txt'.format(dataset_config_dir)) class_id = 1 cld = {} while 1: class_input = class_file.readline() if not class_input: break class_input = class_input[:-1] input_file = open('{0}/models/{1}/points.xyz'.format(opt.dataset_root, class_input)) cld[class_id] = [] while 1: input_line = input_file.readline() if not input_line: break input_line = input_line[:-1] input_line = input_line.split(' ') cld[class_id].append([float(input_line[0]), float(input_line[1]), float(input_line[2])]) input_file.close() cld[class_id] = np.array(cld[class_id]) class_id += 1 data_path = opt.saved_root incr = opt.num_frames//opt.num_keyframes for now in range(0, opt.num_frames, incr): num = 1000001 + now str_num = str(num)[1:] file_name = 'mask/' + str_num + '-object_poses.txt' saved_file = os.path.join(data_path, file_name) f = open(saved_file , 'w') detected_classIDs = [] maskrcnn_result_dir = os.path.join(opt.saved_root, 'mask') detected_idList = open('{0}/{1}-class_ids.txt'.format(maskrcnn_result_dir, str_num)) while 1: id_str = detected_idList.readline() if not id_str: break detected_classIDs.append(int(id_str)) detected_idList.close() file_name = "rgb/" + str_num + "-color.png" rgb_addr = os.path.join(data_path, file_name) file_name = "depth/" + str_num + "-depth.png" depth_addr = os.path.join(data_path, file_name) file_name = "mask/" + str_num + "-mask.png" mask_addr = os.path.join(data_path, file_name) if os.path.isfile(rgb_addr) == False: continue; if os.path.isfile(depth_addr) == False: continue; if os.path.isfile(mask_addr) == False: continue; img = Image.open(rgb_addr) depth = np.array(Image.open(depth_addr)) masks = np.array(Image.open(mask_addr)) my_result_wo_refine = [] my_result = [] for idx in range(len(detected_classIDs)): itemid = detected_classIDs[idx] maskid = idx + 1 try: mask = ma.getmaskarray(ma.masked_equal(masks, maskid)) rmin, rmax, cmin, cmax = get_bbox(mask) print('itemid: {0}\n'.format(itemid)) print('rmin {0}, rmax {1}, cmin {2}, cmax {3}'.format(rmin, rmax, cmin, cmax)) mask_depth = ma.getmaskarray(ma.masked_not_equal(depth, 0)) mask_label = ma.getmaskarray(ma.masked_equal(masks, maskid)) mask = mask_label * mask_depth choose = mask[rmin:rmax, cmin:cmax].flatten().nonzero()[0] if len(choose) > num_points: c_mask = np.zeros(len(choose), dtype=int) c_mask[:num_points] = 1 np.random.shuffle(c_mask) choose = choose[c_mask.nonzero()] else: choose = np.pad(choose, (0, num_points - len(choose)), 'wrap') depth_masked = depth[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) xmap_masked = xmap[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) ymap_masked = ymap[rmin:rmax, cmin:cmax].flatten()[choose][:, np.newaxis].astype(np.float32) choose = np.array([choose]) pt2 = depth_masked / cam_scale pt0 = (ymap_masked - cam_cx) * pt2 / cam_fx pt1 = (xmap_masked - cam_cy) * pt2 / cam_fy cloud = np.concatenate((pt0, pt1, pt2), axis=1) img_masked = np.array(img)[:, :, :3] img_masked = np.transpose(img_masked, (2, 0, 1)) img_masked = img_masked[:, rmin:rmax, cmin:cmax] cloud = torch.from_numpy(cloud.astype(np.float32)) choose = torch.LongTensor(choose.astype(np.int32)) img_masked = norm(torch.from_numpy(img_masked.astype(np.float32))) index = torch.LongTensor([itemid - 1]) cloud = Variable(cloud).cuda() choose = Variable(choose).cuda() img_masked = Variable(img_masked).cuda() index = Variable(index).cuda() cloud = cloud.view(1, num_points, 3) img_masked = img_masked.view(1, 3, img_masked.size()[1], img_masked.size()[2]) pred_r, pred_t, pred_c, emb = estimator(img_masked, cloud, choose, index) pred_r = pred_r / torch.norm(pred_r, dim=2).view(1, num_points, 1) pred_c = pred_c.view(bs, num_points) how_max, which_max = torch.max(pred_c, 1) pred_t = pred_t.view(bs * num_points, 1, 3) points = cloud.view(bs * num_points, 1, 3) my_r = pred_r[0][which_max[0]].view(-1).cpu().data.numpy() my_t = (points + pred_t)[which_max[0]].view(-1).cpu().data.numpy() my_pred = np.append(my_r, my_t) my_result_wo_refine.append(my_pred.tolist()) for ite in range(0, iteration): T = Variable(torch.from_numpy(my_t.astype(np.float32))).cuda().view(1, 3).repeat(num_points, 1).contiguous().view(1, num_points, 3) my_mat = quaternion_matrix(my_r) R = Variable(torch.from_numpy(my_mat[:3, :3].astype(np.float32))).cuda().view(1, 3, 3) my_mat[0:3, 3] = my_t new_cloud = torch.bmm((cloud - T), R).contiguous() pred_r, pred_t = refiner(new_cloud, emb, index) pred_r = pred_r.view(1, 1, -1) pred_r = pred_r / (torch.norm(pred_r, dim=2).view(1, 1, 1)) my_r_2 = pred_r.view(-1).cpu().data.numpy() my_t_2 = pred_t.view(-1).cpu().data.numpy() my_mat_2 = quaternion_matrix(my_r_2) my_mat_2[0:3, 3] = my_t_2 my_mat_final = np.dot(my_mat, my_mat_2) my_r_final = copy.deepcopy(my_mat_final) my_r_final[0:3, 3] = 0 my_r_final = quaternion_from_matrix(my_r_final, True) my_t_final = np.array([my_mat_final[0][3], my_mat_final[1][3], my_mat_final[2][3]]) my_pred = np.append(my_r_final, my_t_final) my_r = my_r_final my_t = my_t_final # Here 'my_pred' is the final pose estimation result after refinement ('my_r': quaternion, 'my_t': translation) my_result.append(my_pred.tolist()) f.write(str(int(itemid))) f.write("\n") np.savetxt(f, my_pred, newline=' ', fmt="%.6f") f.write("\n") print(my_pred) except ZeroDivisionError: print("PoseCNN Detector Lost {0} at No.{1} keyframe".format(itemid, now)) my_result_wo_refine.append([0.0 for i in range(7)]) my_result.append([0.0 for i in range(7)]) f.close() ''' plt.subplot(2, 2, 1) plt.title("rgb") plt.imshow(img) plt.subplot(2, 2, 2) plt.title("depth") plt.imshow(depth) plt.subplot(2, 2, 3) plt.title("mask") plt.imshow(masks) plt.subplot(2, 2, 4) plt.title("mask_label") plt.imshow(masks) plt.show() ''' ================================================ FILE: DenseFusion/tools/train.py ================================================ # -------------------------------------------------------- # DenseFusion 6D Object Pose Estimation by Iterative Dense Fusion # Licensed under The MIT License [see LICENSE for details] # Written by Chen # -------------------------------------------------------- import _init_paths import argparse import os import random import time import numpy as np import torch import torch.nn as nn import torch.nn.parallel import torch.backends.cudnn as cudnn import torch.optim as optim import torch.utils.data import torchvision.datasets as dset import torchvision.transforms as transforms import torchvision.utils as vutils from torch.autograd import Variable from datasets.ycb.dataset import PoseDataset as PoseDataset_ycb from datasets.warehouse.dataset import PoseDataset as PoseDataset_warehouse from datasets.linemod.dataset import PoseDataset as PoseDataset_linemod from lib.network import PoseNet, PoseRefineNet from lib.loss import Loss from lib.loss_refiner import Loss_refine from lib.utils import setup_logger parser = argparse.ArgumentParser() parser.add_argument('--dataset', type=str, default = 'ycb', help='ycb or warehouse or linemod') parser.add_argument('--dataset_root', type=str, default = '', help='dataset root dir (''YCB_Video_Dataset'' or ''Warehouse_Dataset'' or ''Linemod_preprocessed'')') parser.add_argument('--batch_size', type=int, default = 8, help='batch size') parser.add_argument('--workers', type=int, default = 10, help='number of data loading workers') parser.add_argument('--lr', default=0.0001, help='learning rate') parser.add_argument('--lr_rate', default=0.3, help='learning rate decay rate') parser.add_argument('--w', default=0.015, help='learning rate') parser.add_argument('--w_rate', default=0.3, help='learning rate decay rate') parser.add_argument('--decay_margin', default=0.016, help='margin to decay lr & w') parser.add_argument('--refine_margin', default=0.013, help='margin to start the training of iterative refinement') parser.add_argument('--noise_trans', default=0.03, help='range of the random noise of translation added to the training data') parser.add_argument('--iteration', type=int, default = 2, help='number of refinement iterations') parser.add_argument('--nepoch', type=int, default=500, help='max number of epochs to train') parser.add_argument('--resume_posenet', type=str, default = '', help='resume PoseNet model') parser.add_argument('--resume_refinenet', type=str, default = '', help='resume PoseRefineNet model') parser.add_argument('--start_epoch', type=int, default = 1, help='which epoch to start') opt = parser.parse_args() def main(): opt.manualSeed = random.randint(1, 100) random.seed(opt.manualSeed) torch.manual_seed(opt.manualSeed) if opt.dataset == 'ycb': opt.num_objects = 21 #number of object classes in the dataset opt.num_points = 1000 #number of points on the input pointcloud opt.outf = 'trained_models/ycb' #folder to save trained models opt.log_dir = 'experiments/logs/ycb' #folder to save logs opt.repeat_epoch = 1 #number of repeat times for one epoch training elif opt.dataset == 'warehouse': opt.num_objects = 13 opt.num_points = 1000 opt.outf = 'trained_models/warehouse' opt.log_dir = 'experiments/logs/warehouse' opt.repeat_epoch = 1 elif opt.dataset == 'linemod': opt.num_objects = 13 opt.num_points = 500 opt.outf = 'trained_models/linemod' opt.log_dir = 'experiments/logs/linemod' opt.repeat_epoch = 20 else: print('Unknown dataset') return estimator = PoseNet(num_points = opt.num_points, num_obj = opt.num_objects) estimator.cuda() refiner = PoseRefineNet(num_points = opt.num_points, num_obj = opt.num_objects) refiner.cuda() if opt.resume_posenet != '': estimator.load_state_dict(torch.load('{0}/{1}'.format(opt.outf, opt.resume_posenet))) if opt.resume_refinenet != '': refiner.load_state_dict(torch.load('{0}/{1}'.format(opt.outf, opt.resume_refinenet))) opt.refine_start = True opt.decay_start = True opt.lr *= opt.lr_rate opt.w *= opt.w_rate opt.batch_size = int(opt.batch_size / opt.iteration) optimizer = optim.Adam(refiner.parameters(), lr=opt.lr) else: opt.refine_start = False opt.decay_start = False optimizer = optim.Adam(estimator.parameters(), lr=opt.lr) if opt.dataset == 'ycb': dataset = PoseDataset_ycb('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) elif opt.dataset == 'warehouse': dataset = PoseDataset_warehouse('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) elif opt.dataset == 'linemod': dataset = PoseDataset_linemod('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) dataloader = torch.utils.data.DataLoader(dataset, batch_size=1, shuffle=True, num_workers=opt.workers) if opt.dataset == 'ycb': test_dataset = PoseDataset_ycb('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) elif opt.dataset == 'warehouse': test_dataset = PoseDataset_warehouse('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) elif opt.dataset == 'linemod': test_dataset = PoseDataset_linemod('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) testdataloader = torch.utils.data.DataLoader(test_dataset, batch_size=1, shuffle=False, num_workers=opt.workers) opt.sym_list = dataset.get_sym_list() opt.num_points_mesh = dataset.get_num_points_mesh() print('>>>>>>>>----------Dataset loaded!---------<<<<<<<<\nlength of the training set: {0}\nlength of the testing set: {1}\nnumber of sample points on mesh: {2}\nsymmetry object list: {3}'.format(len(dataset), len(test_dataset), opt.num_points_mesh, opt.sym_list)) criterion = Loss(opt.num_points_mesh, opt.sym_list) criterion_refine = Loss_refine(opt.num_points_mesh, opt.sym_list) best_test = np.Inf if opt.start_epoch == 1: for log in os.listdir(opt.log_dir): os.remove(os.path.join(opt.log_dir, log)) st_time = time.time() for epoch in range(opt.start_epoch, opt.nepoch): logger = setup_logger('epoch%d' % epoch, os.path.join(opt.log_dir, 'epoch_%d_log.txt' % epoch)) logger.info('Train time {0}'.format(time.strftime("%Hh %Mm %Ss", time.gmtime(time.time() - st_time)) + ', ' + 'Training started')) train_count = 0 train_dis_avg = 0.0 if opt.refine_start: estimator.eval() refiner.train() else: estimator.train() optimizer.zero_grad() for rep in range(opt.repeat_epoch): for i, data in enumerate(dataloader, 0): points, choose, img, target, model_points, idx = data points, choose, img, target, model_points, idx = Variable(points).cuda(), \ Variable(choose).cuda(), \ Variable(img).cuda(), \ Variable(target).cuda(), \ Variable(model_points).cuda(), \ Variable(idx).cuda() pred_r, pred_t, pred_c, emb = estimator(img, points, choose, idx) loss, dis, new_points, new_target = criterion(pred_r, pred_t, pred_c, target, model_points, idx, points, opt.w, opt.refine_start) if opt.refine_start: for ite in range(0, opt.iteration): pred_r, pred_t = refiner(new_points, emb, idx) dis, new_points, new_target = criterion_refine(pred_r, pred_t, new_target, model_points, idx, new_points) dis.backward() else: loss.backward() train_dis_avg += dis.item() train_count += 1 if train_count % opt.batch_size == 0: logger.info('Train time {0} Epoch {1} Batch {2} Frame {3} Avg_dis:{4}'.format(time.strftime("%Hh %Mm %Ss", time.gmtime(time.time() - st_time)), epoch, int(train_count / opt.batch_size), train_count, train_dis_avg / opt.batch_size)) optimizer.step() optimizer.zero_grad() train_dis_avg = 0 if train_count != 0 and train_count % 1000 == 0: if opt.refine_start: torch.save(refiner.state_dict(), '{0}/pose_refine_model_current.pth'.format(opt.outf)) else: torch.save(estimator.state_dict(), '{0}/pose_model_current.pth'.format(opt.outf)) print('>>>>>>>>----------epoch {0} train finish---------<<<<<<<<'.format(epoch)) logger = setup_logger('epoch%d_test' % epoch, os.path.join(opt.log_dir, 'epoch_%d_test_log.txt' % epoch)) logger.info('Test time {0}'.format(time.strftime("%Hh %Mm %Ss", time.gmtime(time.time() - st_time)) + ', ' + 'Testing started')) test_dis = 0.0 test_count = 0 estimator.eval() refiner.eval() for j, data in enumerate(testdataloader, 0): points, choose, img, target, model_points, idx = data points, choose, img, target, model_points, idx = Variable(points).cuda(), \ Variable(choose).cuda(), \ Variable(img).cuda(), \ Variable(target).cuda(), \ Variable(model_points).cuda(), \ Variable(idx).cuda() pred_r, pred_t, pred_c, emb = estimator(img, points, choose, idx) _, dis, new_points, new_target = criterion(pred_r, pred_t, pred_c, target, model_points, idx, points, opt.w, opt.refine_start) if opt.refine_start: for ite in range(0, opt.iteration): pred_r, pred_t = refiner(new_points, emb, idx) dis, new_points, new_target = criterion_refine(pred_r, pred_t, new_target, model_points, idx, new_points) test_dis += dis.item() logger.info('Test time {0} Test Frame No.{1} dis:{2}'.format(time.strftime("%Hh %Mm %Ss", time.gmtime(time.time() - st_time)), test_count, dis)) test_count += 1 test_dis = test_dis / test_count logger.info('Test time {0} Epoch {1} TEST FINISH Avg dis: {2}'.format(time.strftime("%Hh %Mm %Ss", time.gmtime(time.time() - st_time)), epoch, test_dis)) if test_dis <= best_test: best_test = test_dis if opt.refine_start: torch.save(refiner.state_dict(), '{0}/pose_refine_model_{1}_{2}.pth'.format(opt.outf, epoch, test_dis)) else: torch.save(estimator.state_dict(), '{0}/pose_model_{1}_{2}.pth'.format(opt.outf, epoch, test_dis)) print(epoch, '>>>>>>>>----------BEST TEST MODEL SAVED---------<<<<<<<<') if best_test < opt.decay_margin and not opt.decay_start: opt.decay_start = True opt.lr *= opt.lr_rate opt.w *= opt.w_rate optimizer = optim.Adam(estimator.parameters(), lr=opt.lr) if best_test < opt.refine_margin and not opt.refine_start: opt.refine_start = True opt.batch_size = int(opt.batch_size / opt.iteration) optimizer = optim.Adam(refiner.parameters(), lr=opt.lr) if opt.dataset == 'ycb': dataset = PoseDataset_ycb('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) if opt.dataset == 'warehouse': dataset = PoseDataset_warehouse('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) elif opt.dataset == 'linemod': dataset = PoseDataset_linemod('train', opt.num_points, True, opt.dataset_root, opt.noise_trans, opt.refine_start) dataloader = torch.utils.data.DataLoader(dataset, batch_size=1, shuffle=True, num_workers=opt.workers) if opt.dataset == 'ycb': test_dataset = PoseDataset_ycb('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) if opt.dataset == 'warehouse': test_dataset = PoseDataset_warehouse('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) elif opt.dataset == 'linemod': test_dataset = PoseDataset_linemod('test', opt.num_points, False, opt.dataset_root, 0.0, opt.refine_start) testdataloader = torch.utils.data.DataLoader(test_dataset, batch_size=1, shuffle=False, num_workers=opt.workers) opt.sym_list = dataset.get_sym_list() opt.num_points_mesh = dataset.get_num_points_mesh() print('>>>>>>>>----------Dataset loaded!---------<<<<<<<<\nlength of the training set: {0}\nlength of the testing set: {1}\nnumber of sample points on mesh: {2}\nsymmetry object list: {3}'.format(len(dataset), len(test_dataset), opt.num_points_mesh, opt.sym_list)) criterion = Loss(opt.num_points_mesh, opt.sym_list) criterion_refine = Loss_refine(opt.num_points_mesh, opt.sym_list) if __name__ == '__main__': main() ================================================ FILE: DenseFusion/trained_checkpoints/warehouse/note ================================================ ================================================ FILE: DenseFusion/trained_models/warehouse/note ================================================ ================================================ FILE: Mask_RCNN/LICENSE ================================================ Mask R-CNN The MIT License (MIT) Copyright (c) 2017 Matterport, Inc. Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ================================================ FILE: Mask_RCNN/MANIFEST.in ================================================ include README.md include LICENSE include requirements.txt ================================================ FILE: Mask_RCNN/README.md ================================================ # Mask R-CNN for Object Detection and Segmentation This is an implementation of instance segmentation used in [Object-RPE](https://sites.google.com/view/object-rpe). The original version is from [matterport](https://github.com/matterport/Mask_RCNN). The model generates bounding boxes and segmentation masks for each instance of an object in the image. It's based on Feature Pyramid Network (FPN) and a ResNet101 backbone. ## Requirements Python 3.4, TensorFlow 1.3, Keras 2.0.8 and other common packages listed in `requirements.txt`. ## Installation 1. Install dependencies ```bash pip3 install -r requirements.txt ``` 2. Run setup from the directory ~/catkin_ws/src/Object-RPE/Mask_RCNN ```bash sudo python3 setup.py install ``` ## Train and evaluate model 1. To train ```bash python3 train.py --dataset=/Warehouse_Dataset/data --weights==coco ``` 2. To evaluate ```bash sudo python3 eval.py ``` Read rgb and round-truth images from rgb/ and gt/ folders in .../Object-RPE/data, then save results in .../Object-RPE/data/mask ================================================ FILE: Mask_RCNN/dataset_format ================================================ { "34020010494_e5cb88e1c4_k.jpg1115004": { "fileref":"", "size":1115004, "filename":"34020010494_e5cb88e1c4_k.jpg", "base64_img_data":"", "file_attributes":{}, "regions": { "0": { "shape_attributes": { "name":"polygon", "all_points_x": [1020,1000,994,1003,1023,1050,1089,1134,1190,1265,1321,1361,1403,1428,1442,1445,1441,1427,1400,1361,1316,1269,1228,1198,1207,1210,1190,1177,1172,1174,1170,1153,1127,1104,1061,1032,1020], "all_points_y":[963,899,841,787,738,700,663,638,621,619,643,672,720,765,800,860,896,942,990,1035,1079,1112,1129,1134,1144,1153,1166,1166,1150,1136,1129,1122,1112,1084,1037,989,963] }, "region_attributes": {} } } }, "18849792632_aad23ad513_k.jpg522255": { "fileref":"", "size":522255, "filename":"18849792632_aad23ad513_k.jpg", "base64_img_data":"", "file_attributes":{}, "regions": { "0": { "shape_attributes": { "name":"polygon", "all_points_x":[618,657,688,707,741,760,779,791,820,836,844,860,868,871,871,868,864,854,840,824,809,795,778,759,741,719,699,677,664,641,623,606,601,582,567,554,535,534,543,560,579,597,618], "all_points_y":[385,370,365,365,373,382,390,404,432,451,472,507,541,561,589,612,635,668,698,727,752,764,784,807,804,803,805,811,796,772,754,735,729,704,682,648,593,530,483,446,420,401,385] }, "region_attributes": {} }, "1": { "shape_attributes": { "name":"polygon", "all_points_x":[942,960,979,990,1006,1008,1012,1013,984,959,933,906,879,858,844,831,825,816,806,795,811,826,842,856,869,871,863,854,840,865,891,917,942], "all_points_y":[480,494,515,531,563,581,597,619,623,630,642,657,683,715,742,780,805,792,780,765,748,723,694,661,616,564,521,490,466,457,458,464,480] }, "region_attributes": {} }, "2": { "shape_attributes": { "name":"polygon", "all_points_x":[1068,1087,1111,1126,1141,1150,1161,1161,1159,1149,1135,1122,1103,1081,1054,1024,996,976,960,941,924,912,903,905,898,903,906,906,903,892,881,863,845,830,823,823,828,837,848,873,894,923,953,988,1021,1046,1068], "all_points_y":[632,641,660,677,695,723,756,782,817,849,886,906,929,951,970,991,1006,1015,1029,1041,1047,1050,1054,1059,1064,1048,1028,996,960,928,905,877,856,844,838,821,796,764,734,692,667,647,632,622,619,623,632] }, "region_attributes": {} }, "3": { "shape_attributes": { "name":"polygon", "all_points_x":[651,667,686,719,737,751,766,783,797,808,827,846,861,876,890,903,906,907,898,884,867,852,831,814,798,782,766,753,749,750,751,751,746,740,735,732,732,731,719,707,689,674,657,638,617,598,584,569,564,566,573,586,604,626,651], "all_points_y":[826,817,809,803,803,805,810,816,821,827,842,856,874,897,926,956,999,1027,1061,1101,1128,1150,1172,1189,1202,1216,1227,1229,1231,1234,1241,1243,1245,1243,1242,1238,1232,1227,1224,1216,1204,1193,1182,1168,1142,1114,1085,1045,1001,948,922,890,861,842,826] }, "region_attributes": {} }, "4": { "shape_attributes": { "name":"polygon", "all_points_x":[1082,1093,1103,1113,1120,1122,1122,1118,1107,1093,1078,1061,1041,1017,986,959,938,922,906,877,861,845,830,830,824,823,817,813,813,821,817,811,807,809,809,807,805,825,842,860,881,891,896,906,906,912,936,964,972,992,1011,1023,1048,1066,1082], "all_points_y":[1026,1039,1054,1074,1101,1127,1147,1181,1206,1234,1251,1271,1288,1305,1319,1327,1334,1336,1342,1352,1359,1360,1357,1356,1358,1364,1363,1357,1348,1350,1343,1331,1313,1292,1268,1240,1200,1179,1161,1140,1105,1080,1064,1060,1054,1048,1044,1028,1021,1008,999,991,1000,1011,1026] }, "region_attributes": {} }, "5": { "shape_attributes": { "name":"polygon", "all_points_x":[803,791,781,775,750,737,726,705,705,706,700,694,693,693,694,688,678,667,660,650,644,637,627,614,600,609,625,639,651,665,678,688,694,700,707,710,710,721,725,735,739,737,732,725,718,710,722,731,731,734,741,748,751,749,756,771,790,798,805,808,807,807,811,815,822,813,812,816,817,813,803], "all_points_y":[1426,1453,1474,1483,1515,1532,1551,1558,1565,1572,1575,1574,1570,1564,1560,1558,1555,1553,1547,1538,1529,1523,1517,1508,1497,1496,1496,1494,1493,1492,1490,1486,1486,1486,1480,1474,1467,1445,1420,1377,1350,1322,1284,1257,1235,1219,1226,1226,1234,1240,1243,1246,1241,1232,1231,1239,1261,1275,1289,1297,1308,1318,1326,1342,1349,1349,1357,1363,1373,1394,1426] }, "region_attributes": {} }, "6": { "shape_attributes": { "name":"polygon", "all_points_x":[390,395,407,435,456,483,506,538,565,591,611,620,635,653,676,695,711,715,722,729,732,739,738,730,725,714,708,710,700,692,680,662,636,620,603,577,548,517,501,478,452,429,414,399,394,390,390], "all_points_y":[1282,1249,1207,1170,1151,1138,1130,1122,1126,1131,1139,1145,1165,1181,1196,1208,1218,1226,1243,1270,1292,1327,1365,1404,1425,1458,1472,1477,1487,1486,1491,1491,1495,1495,1496,1496,1490,1479,1469,1457,1437,1412,1389,1356,1336,1313,1282] }, "region_attributes": {} }, "7": { "shape_attributes": { "name":"polygon", "all_points_x":[417,401,386,377,367,361,357,355,355,366,375,393,409,427,447,472,493,503,516,530,550,568,575,582,587,581,571,571,557,540,512,492,471,451,433,417], "all_points_y":[1087,1073,1054,1037,1020,1002,976,954,926,938,952,972,983,994,1004,1016,1025,1034,1039,1048,1046,1044,1062,1078,1093,1104,1124,1126,1124,1122,1130,1134,1123,1113,1099,1087] }, "region_attributes": {} }, "8": { "shape_attributes": { "name":"polygon", "all_points_x":[309,312,320,335,349,367,386,408,431,464,488,534,554,569,581,592,603,618,622,629,634,640,633,622,604,590,573,566,566,566,564,567,569,558,533,516,503,489,466,443,425,404,392,376,363,352,338,320,307,307,309], "all_points_y":[754,744,717,693,675,659,649,640,638,637,643,663,677,688,704,719,734,762,776,794,814,830,838,846,859,885,921,949,966,982,1007,1027,1044,1045,1048,1041,1033,1024,1013,1004,994,981,969,955,936,924,898,861,808,775,754] }, "region_attributes": {} }, "9": { "shape_attributes": { "name":"polygon", "all_points_x":[467,478,492,508,522,534,533,535,536,546,556,570,585,602,620,670,678,641,633,623,612,600,583,567,537,499,479,462,461,467], "all_points_y":[610,586,562,543,531,522,539,564,595,622,656,685,708,729,752,802,810,830,805,778,750,731,707,687,665,648,639,636,628,610] }, "region_attributes": {} } } } } ================================================ FILE: Mask_RCNN/docker/Dockerfile ================================================ FROM nvidia/cuda:9.0-cudnn7-devel-ubuntu16.04 MAINTAINER Dinh-Cuong Hoang # Supress warnings about missing front-end. As recommended at: # http://stackoverflow.com/questions/22466255/is-it-possibe-to-answer-dialog-questions-when-installing-under-docker ARG DEBIAN_FRONTEND=noninteractive # Essentials: developer tools, build tools, OpenBLAS RUN apt-get update && apt-get install -y --no-install-recommends \ apt-utils git curl vim unzip openssh-client wget \ build-essential cmake \ libopenblas-dev # Python 3.5 # For convenience, alias (but don't sym-link) python & pip to python3 & pip3 as recommended in: # http://askubuntu.com/questions/351318/changing-symlink-python-to-python3-causes-problems RUN apt-get install -y --no-install-recommends python3.5 python3.5-dev python3-pip python3-tk && \ pip3 install --no-cache-dir --upgrade pip setuptools && \ echo "alias python='python3'" >> /root/.bash_aliases && \ echo "alias pip='pip3'" >> /root/.bash_aliases # Pillow and it's dependencies RUN apt-get install -y --no-install-recommends libjpeg-dev zlib1g-dev && \ pip3 --no-cache-dir install Pillow # Science libraries and other common packages RUN pip3 --no-cache-dir install \ numpy scipy sklearn scikit-image imgaug opencv-python IPython[all] matplotlib Cython requests # Jupyter Notebook # Allow access from outside the container, and skip trying to open a browser. # NOTE: disable authentication token for convenience. DON'T DO THIS ON A PUBLIC SERVER. RUN pip3 --no-cache-dir install jupyter && \ mkdir /root/.jupyter && \ echo "c.NotebookApp.ip = '*'" \ "\nc.NotebookApp.open_browser = False" \ "\nc.NotebookApp.token = ''" \ > /root/.jupyter/jupyter_notebook_config.py EXPOSE 8888 # Tensorflow 1.11 - GPU RUN pip3 install --no-cache-dir tensorflow-gpu==1.11 # Expose port for TensorBoard EXPOSE 6006 # Keras 2.1.5 RUN pip3 install --no-cache-dir --upgrade h5py pydot_ng keras ================================================ FILE: Mask_RCNN/docker/docker_build.sh ================================================ #!/bin/bash # # This script runs docker build to create the maskrcnn-gpu docker image. # set -exu sudo nvidia-docker build --tag maskrcnn-gpu ./ ================================================ FILE: Mask_RCNN/docker/docker_run.sh ================================================ #!/bin/bash # # Usage: ./docker_run.sh [/path/to/data] # # This script calls `nvidia-docker run` to start the labelfusion # container with an interactive bash session. This script sets # the required environment variables and mounts the labelfusion # source directory as a volume in the docker container. If the # path to a data directory is given then the data directory is # also mounted as a volume. # image_name=hoangcuongbk80/maskrcnn-gpu:latest sudo nvidia-docker run --name mask-rcnn -it --rm -v /home/aass/Hoang-Cuong/Mask_RCNN:/maskrcnn hoangcuongbk80/maskrcnn-gpu /bin/bash ================================================ FILE: Mask_RCNN/mask_rcnn.egg-info/PKG-INFO ================================================ Metadata-Version: 1.2 Name: mask-rcnn Version: 2.1 Summary: Mask R-CNN for object detection and instance segmentation Home-page: https://github.com/matterport/Mask_RCNN Author: Matterport Author-email: waleed.abdulla@gmail.com License: MIT Description: This is an implementation of Mask R-CNN on Python 3, Keras, and TensorFlow. The model generates bounding boxes and segmentation masks for each instance of an object in the image. It's based on Feature Pyramid Network (FPN) and a ResNet101 backbone. Keywords: image instance segmentation object detection mask rcnn r-cnn tensorflow keras Platform: UNKNOWN Classifier: Development Status :: 5 - Production/Stable Classifier: Environment :: Console Classifier: Intended Audience :: Developers Classifier: Intended Audience :: Information Technology Classifier: Intended Audience :: Education Classifier: Intended Audience :: Science/Research Classifier: License :: OSI Approved :: MIT License Classifier: Natural Language :: English Classifier: Operating System :: OS Independent Classifier: Topic :: Scientific/Engineering :: Artificial Intelligence Classifier: Topic :: Scientific/Engineering :: Image Recognition Classifier: Topic :: Scientific/Engineering :: Visualization Classifier: Topic :: Scientific/Engineering :: Image Segmentation Classifier: Programming Language :: Python :: 3.4 Classifier: Programming Language :: Python :: 3.5 Classifier: Programming Language :: Python :: 3.6 Requires-Python: >=3.4 ================================================ FILE: Mask_RCNN/mask_rcnn.egg-info/SOURCES.txt ================================================ LICENSE MANIFEST.in README.md requirements.txt setup.cfg setup.py mask_rcnn.egg-info/PKG-INFO mask_rcnn.egg-info/SOURCES.txt mask_rcnn.egg-info/dependency_links.txt mask_rcnn.egg-info/top_level.txt mrcnn/__init__.py mrcnn/config.py mrcnn/model.py mrcnn/parallel_model.py mrcnn/utils.py mrcnn/visualize.py ================================================ FILE: Mask_RCNN/mask_rcnn.egg-info/dependency_links.txt ================================================ ================================================ FILE: Mask_RCNN/mask_rcnn.egg-info/top_level.txt ================================================ mrcnn ================================================ FILE: Mask_RCNN/mrcnn/__init__.py ================================================ ================================================ FILE: Mask_RCNN/mrcnn/config.py ================================================ """ Mask R-CNN Base Configurations class. Copyright (c) 2017 Matterport, Inc. Licensed under the MIT License (see LICENSE for details) Written by Waleed Abdulla """ import numpy as np # Base Configuration Class # Don't use this class directly. Instead, sub-class it and override # the configurations you need to change. class Config(object): """Base configuration class. For custom configurations, create a sub-class that inherits from this one and override properties that need to be changed. """ # Name the configurations. For example, 'COCO', 'Experiment 3', ...etc. # Useful if your code needs to do things differently depending on which # experiment is running. NAME = None # Override in sub-classes # NUMBER OF GPUs to use. When using only a CPU, this needs to be set to 1. GPU_COUNT = 1 # Number of images to train with on each GPU. A 12GB GPU can typically # handle 2 images of 1024x1024px. # Adjust based on your GPU memory and image sizes. Use the highest # number that your GPU can handle for best performance. IMAGES_PER_GPU = 2 # Number of training steps per epoch # This doesn't need to match the size of the training set. Tensorboard # updates are saved at the end of each epoch, so setting this to a # smaller number means getting more frequent TensorBoard updates. # Validation stats are also calculated at each epoch end and they # might take a while, so don't set this too small to avoid spending # a lot of time on validation stats. STEPS_PER_EPOCH = 1000 # Number of validation steps to run at the end of every training epoch. # A bigger number improves accuracy of validation stats, but slows # down the training. VALIDATION_STEPS = 50 # Backbone network architecture # Supported values are: resnet50, resnet101. # You can also provide a callable that should have the signature # of model.resnet_graph. If you do so, you need to supply a callable # to COMPUTE_BACKBONE_SHAPE as well BACKBONE = "resnet101" # Only useful if you supply a callable to BACKBONE. Should compute # the shape of each layer of the FPN Pyramid. # See model.compute_backbone_shapes COMPUTE_BACKBONE_SHAPE = None # The strides of each layer of the FPN Pyramid. These values # are based on a Resnet101 backbone. BACKBONE_STRIDES = [4, 8, 16, 32, 64] # Size of the fully-connected layers in the classification graph FPN_CLASSIF_FC_LAYERS_SIZE = 1024 # Size of the top-down layers used to build the feature pyramid TOP_DOWN_PYRAMID_SIZE = 256 # Number of classification classes (including background) NUM_CLASSES = 1 # Override in sub-classes 1 # Length of square anchor side in pixels RPN_ANCHOR_SCALES = (32, 64, 128, 256, 512) # Ratios of anchors at each cell (width/height) # A value of 1 represents a square anchor, and 0.5 is a wide anchor RPN_ANCHOR_RATIOS = [0.5, 1, 2] # Anchor stride # If 1 then anchors are created for each cell in the backbone feature map. # If 2, then anchors are created for every other cell, and so on. RPN_ANCHOR_STRIDE = 1 # Non-max suppression threshold to filter RPN proposals. # You can increase this during training to generate more propsals. RPN_NMS_THRESHOLD = 0.7 # How many anchors per image to use for RPN training RPN_TRAIN_ANCHORS_PER_IMAGE = 256 # ROIs kept after tf.nn.top_k and before non-maximum suppression PRE_NMS_LIMIT = 6000 # ROIs kept after non-maximum suppression (training and inference) POST_NMS_ROIS_TRAINING = 2000 POST_NMS_ROIS_INFERENCE = 1000 # If enabled, resizes instance masks to a smaller size to reduce # memory load. Recommended when using high-resolution images. USE_MINI_MASK = True MINI_MASK_SHAPE = (56, 56) # (height, width) of the mini-mask # Input image resizing # Generally, use the "square" resizing mode for training and predicting # and it should work well in most cases. In this mode, images are scaled # up such that the small side is = IMAGE_MIN_DIM, but ensuring that the # scaling doesn't make the long side > IMAGE_MAX_DIM. Then the image is # padded with zeros to make it a square so multiple images can be put # in one batch. # Available resizing modes: # none: No resizing or padding. Return the image unchanged. # square: Resize and pad with zeros to get a square image # of size [max_dim, max_dim]. # pad64: Pads width and height with zeros to make them multiples of 64. # If IMAGE_MIN_DIM or IMAGE_MIN_SCALE are not None, then it scales # up before padding. IMAGE_MAX_DIM is ignored in this mode. # The multiple of 64 is needed to ensure smooth scaling of feature # maps up and down the 6 levels of the FPN pyramid (2**6=64). # crop: Picks random crops from the image. First, scales the image based # on IMAGE_MIN_DIM and IMAGE_MIN_SCALE, then picks a random crop of # size IMAGE_MIN_DIM x IMAGE_MIN_DIM. Can be used in training only. # IMAGE_MAX_DIM is not used in this mode. IMAGE_RESIZE_MODE = "square" IMAGE_MIN_DIM = 800 IMAGE_MAX_DIM = 1024 # Minimum scaling ratio. Checked after MIN_IMAGE_DIM and can force further # up scaling. For example, if set to 2 then images are scaled up to double # the width and height, or more, even if MIN_IMAGE_DIM doesn't require it. # Howver, in 'square' mode, it can be overruled by IMAGE_MAX_DIM. IMAGE_MIN_SCALE = 0 # Number of color channels per image. RGB = 3, grayscale = 1, RGB-D = 4 # Changing this requires other changes in the code. See the WIKI for more # details: https://github.com/matterport/Mask_RCNN/wiki IMAGE_CHANNEL_COUNT = 3 # Image mean (RGB) MEAN_PIXEL = np.array([123.7, 116.8, 103.9]) # Number of ROIs per image to feed to classifier/mask heads # The Mask RCNN paper uses 512 but often the RPN doesn't generate # enough positive proposals to fill this and keep a positive:negative # ratio of 1:3. You can increase the number of proposals by adjusting # the RPN NMS threshold. TRAIN_ROIS_PER_IMAGE = 200 # Percent of positive ROIs used to train classifier/mask heads ROI_POSITIVE_RATIO = 0.33 # Pooled ROIs POOL_SIZE = 7 MASK_POOL_SIZE = 14 # Shape of output mask # To change this you also need to change the neural network mask branch MASK_SHAPE = [28, 28] # Maximum number of ground truth instances to use in one image MAX_GT_INSTANCES = 100 # Bounding box refinement standard deviation for RPN and final detections. RPN_BBOX_STD_DEV = np.array([0.1, 0.1, 0.2, 0.2]) BBOX_STD_DEV = np.array([0.1, 0.1, 0.2, 0.2]) # Max number of final detections DETECTION_MAX_INSTANCES = 100 # Minimum probability value to accept a detected instance # ROIs below this threshold are skipped DETECTION_MIN_CONFIDENCE = 0.7 # Non-maximum suppression threshold for detection DETECTION_NMS_THRESHOLD = 0.3 # Learning rate and momentum # The Mask RCNN paper uses lr=0.02, but on TensorFlow it causes # weights to explode. Likely due to differences in optimizer # implementation. LEARNING_RATE = 0.001 LEARNING_MOMENTUM = 0.9 # Weight decay regularization WEIGHT_DECAY = 0.0001 # Loss weights for more precise optimization. # Can be used for R-CNN training setup. LOSS_WEIGHTS = { "rpn_class_loss": 1., "rpn_bbox_loss": 1., "mrcnn_class_loss": 1., "mrcnn_bbox_loss": 1., "mrcnn_mask_loss": 1. } # Use RPN ROIs or externally generated ROIs for training # Keep this True for most situations. Set to False if you want to train # the head branches on ROI generated by code rather than the ROIs from # the RPN. For example, to debug the classifier head without having to # train the RPN. USE_RPN_ROIS = True # Train or freeze batch normalization layers # None: Train BN layers. This is the normal mode # False: Freeze BN layers. Good when using a small batch size # True: (don't use). Set layer in training mode even when predicting TRAIN_BN = False # Defaulting to False since batch size is often small # Gradient norm clipping GRADIENT_CLIP_NORM = 5.0 def __init__(self): """Set values of computed attributes.""" # Effective batch size self.BATCH_SIZE = self.IMAGES_PER_GPU * self.GPU_COUNT # Input image size if self.IMAGE_RESIZE_MODE == "crop": self.IMAGE_SHAPE = np.array([self.IMAGE_MIN_DIM, self.IMAGE_MIN_DIM, self.IMAGE_CHANNEL_COUNT]) else: self.IMAGE_SHAPE = np.array([self.IMAGE_MAX_DIM, self.IMAGE_MAX_DIM, self.IMAGE_CHANNEL_COUNT]) # Image meta data length # See compose_image_meta() for details self.IMAGE_META_SIZE = 1 + 3 + 3 + 4 + 1 + self.NUM_CLASSES def display(self): """Display Configuration values.""" print("\nConfigurations:") for a in dir(self): if not a.startswith("__") and not callable(getattr(self, a)): print("{:30} {}".format(a, getattr(self, a))) print("\n") ================================================ FILE: Mask_RCNN/mrcnn/model.py ================================================ """ Mask R-CNN The main Mask R-CNN model implementation. Copyright (c) 2017 Matterport, Inc. Licensed under the MIT License (see LICENSE for details) Written by Waleed Abdulla """ import os import random import datetime import re import math import logging from collections import OrderedDict import multiprocessing import numpy as np import tensorflow as tf import keras import keras.backend as K import keras.layers as KL import keras.engine as KE import keras.models as KM from mrcnn import utils # Requires TensorFlow 1.3+ and Keras 2.0.8+. from distutils.version import LooseVersion assert LooseVersion(tf.__version__) >= LooseVersion("1.3") assert LooseVersion(keras.__version__) >= LooseVersion('2.0.8') ############################################################ # Utility Functions ############################################################ def log(text, array=None): """Prints a text message. And, optionally, if a Numpy array is provided it prints it's shape, min, and max values. """ if array is not None: text = text.ljust(25) text += ("shape: {:20} min: {:10.5f} max: {:10.5f} {}".format( str(array.shape), array.min() if array.size else "", array.max() if array.size else "", array.dtype)) print(text) class BatchNorm(KL.BatchNormalization): """Extends the Keras BatchNormalization class to allow a central place to make changes if needed. Batch normalization has a negative effect on training if batches are small so this layer is often frozen (via setting in Config class) and functions as linear layer. """ def call(self, inputs, training=None): """ Note about training values: None: Train BN layers. This is the normal mode False: Freeze BN layers. Good when batch size is small True: (don't use). Set layer in training mode even when making inferences """ return super(self.__class__, self).call(inputs, training=training) def compute_backbone_shapes(config, image_shape): """Computes the width and height of each stage of the backbone network. Returns: [N, (height, width)]. Where N is the number of stages """ if callable(config.BACKBONE): return config.COMPUTE_BACKBONE_SHAPE(image_shape) # Currently supports ResNet only assert config.BACKBONE in ["resnet50", "resnet101"] return np.array( [[int(math.ceil(image_shape[0] / stride)), int(math.ceil(image_shape[1] / stride))] for stride in config.BACKBONE_STRIDES]) ############################################################ # Resnet Graph ############################################################ # Code adopted from: # https://github.com/fchollet/deep-learning-models/blob/master/resnet50.py def identity_block(input_tensor, kernel_size, filters, stage, block, use_bias=True, train_bn=True): """The identity_block is the block that has no conv layer at shortcut # Arguments input_tensor: input tensor kernel_size: default 3, the kernel size of middle conv layer at main path filters: list of integers, the nb_filters of 3 conv layer at main path stage: integer, current stage label, used for generating layer names block: 'a','b'..., current block label, used for generating layer names use_bias: Boolean. To use or not use a bias in conv layers. train_bn: Boolean. Train or freeze Batch Norm layers """ nb_filter1, nb_filter2, nb_filter3 = filters conv_name_base = 'res' + str(stage) + block + '_branch' bn_name_base = 'bn' + str(stage) + block + '_branch' x = KL.Conv2D(nb_filter1, (1, 1), name=conv_name_base + '2a', use_bias=use_bias)(input_tensor) x = BatchNorm(name=bn_name_base + '2a')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.Conv2D(nb_filter2, (kernel_size, kernel_size), padding='same', name=conv_name_base + '2b', use_bias=use_bias)(x) x = BatchNorm(name=bn_name_base + '2b')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.Conv2D(nb_filter3, (1, 1), name=conv_name_base + '2c', use_bias=use_bias)(x) x = BatchNorm(name=bn_name_base + '2c')(x, training=train_bn) x = KL.Add()([x, input_tensor]) x = KL.Activation('relu', name='res' + str(stage) + block + '_out')(x) return x def conv_block(input_tensor, kernel_size, filters, stage, block, strides=(2, 2), use_bias=True, train_bn=True): """conv_block is the block that has a conv layer at shortcut # Arguments input_tensor: input tensor kernel_size: default 3, the kernel size of middle conv layer at main path filters: list of integers, the nb_filters of 3 conv layer at main path stage: integer, current stage label, used for generating layer names block: 'a','b'..., current block label, used for generating layer names use_bias: Boolean. To use or not use a bias in conv layers. train_bn: Boolean. Train or freeze Batch Norm layers Note that from stage 3, the first conv layer at main path is with subsample=(2,2) And the shortcut should have subsample=(2,2) as well """ nb_filter1, nb_filter2, nb_filter3 = filters conv_name_base = 'res' + str(stage) + block + '_branch' bn_name_base = 'bn' + str(stage) + block + '_branch' x = KL.Conv2D(nb_filter1, (1, 1), strides=strides, name=conv_name_base + '2a', use_bias=use_bias)(input_tensor) x = BatchNorm(name=bn_name_base + '2a')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.Conv2D(nb_filter2, (kernel_size, kernel_size), padding='same', name=conv_name_base + '2b', use_bias=use_bias)(x) x = BatchNorm(name=bn_name_base + '2b')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.Conv2D(nb_filter3, (1, 1), name=conv_name_base + '2c', use_bias=use_bias)(x) x = BatchNorm(name=bn_name_base + '2c')(x, training=train_bn) shortcut = KL.Conv2D(nb_filter3, (1, 1), strides=strides, name=conv_name_base + '1', use_bias=use_bias)(input_tensor) shortcut = BatchNorm(name=bn_name_base + '1')(shortcut, training=train_bn) x = KL.Add()([x, shortcut]) x = KL.Activation('relu', name='res' + str(stage) + block + '_out')(x) return x def resnet_graph(input_image, architecture, stage5=False, train_bn=True): """Build a ResNet graph. architecture: Can be resnet50 or resnet101 stage5: Boolean. If False, stage5 of the network is not created train_bn: Boolean. Train or freeze Batch Norm layers """ assert architecture in ["resnet50", "resnet101"] # Stage 1 x = KL.ZeroPadding2D((3, 3))(input_image) x = KL.Conv2D(64, (7, 7), strides=(2, 2), name='conv1', use_bias=True)(x) x = BatchNorm(name='bn_conv1')(x, training=train_bn) x = KL.Activation('relu')(x) C1 = x = KL.MaxPooling2D((3, 3), strides=(2, 2), padding="same")(x) # Stage 2 x = conv_block(x, 3, [64, 64, 256], stage=2, block='a', strides=(1, 1), train_bn=train_bn) x = identity_block(x, 3, [64, 64, 256], stage=2, block='b', train_bn=train_bn) C2 = x = identity_block(x, 3, [64, 64, 256], stage=2, block='c', train_bn=train_bn) # Stage 3 x = conv_block(x, 3, [128, 128, 512], stage=3, block='a', train_bn=train_bn) x = identity_block(x, 3, [128, 128, 512], stage=3, block='b', train_bn=train_bn) x = identity_block(x, 3, [128, 128, 512], stage=3, block='c', train_bn=train_bn) C3 = x = identity_block(x, 3, [128, 128, 512], stage=3, block='d', train_bn=train_bn) # Stage 4 x = conv_block(x, 3, [256, 256, 1024], stage=4, block='a', train_bn=train_bn) block_count = {"resnet50": 5, "resnet101": 22}[architecture] for i in range(block_count): x = identity_block(x, 3, [256, 256, 1024], stage=4, block=chr(98 + i), train_bn=train_bn) C4 = x # Stage 5 if stage5: x = conv_block(x, 3, [512, 512, 2048], stage=5, block='a', train_bn=train_bn) x = identity_block(x, 3, [512, 512, 2048], stage=5, block='b', train_bn=train_bn) C5 = x = identity_block(x, 3, [512, 512, 2048], stage=5, block='c', train_bn=train_bn) else: C5 = None return [C1, C2, C3, C4, C5] ############################################################ # Proposal Layer ############################################################ def apply_box_deltas_graph(boxes, deltas): """Applies the given deltas to the given boxes. boxes: [N, (y1, x1, y2, x2)] boxes to update deltas: [N, (dy, dx, log(dh), log(dw))] refinements to apply """ # Convert to y, x, h, w height = boxes[:, 2] - boxes[:, 0] width = boxes[:, 3] - boxes[:, 1] center_y = boxes[:, 0] + 0.5 * height center_x = boxes[:, 1] + 0.5 * width # Apply deltas center_y += deltas[:, 0] * height center_x += deltas[:, 1] * width height *= tf.exp(deltas[:, 2]) width *= tf.exp(deltas[:, 3]) # Convert back to y1, x1, y2, x2 y1 = center_y - 0.5 * height x1 = center_x - 0.5 * width y2 = y1 + height x2 = x1 + width result = tf.stack([y1, x1, y2, x2], axis=1, name="apply_box_deltas_out") return result def clip_boxes_graph(boxes, window): """ boxes: [N, (y1, x1, y2, x2)] window: [4] in the form y1, x1, y2, x2 """ # Split wy1, wx1, wy2, wx2 = tf.split(window, 4) y1, x1, y2, x2 = tf.split(boxes, 4, axis=1) # Clip y1 = tf.maximum(tf.minimum(y1, wy2), wy1) x1 = tf.maximum(tf.minimum(x1, wx2), wx1) y2 = tf.maximum(tf.minimum(y2, wy2), wy1) x2 = tf.maximum(tf.minimum(x2, wx2), wx1) clipped = tf.concat([y1, x1, y2, x2], axis=1, name="clipped_boxes") clipped.set_shape((clipped.shape[0], 4)) return clipped class ProposalLayer(KE.Layer): """Receives anchor scores and selects a subset to pass as proposals to the second stage. Filtering is done based on anchor scores and non-max suppression to remove overlaps. It also applies bounding box refinement deltas to anchors. Inputs: rpn_probs: [batch, num_anchors, (bg prob, fg prob)] rpn_bbox: [batch, num_anchors, (dy, dx, log(dh), log(dw))] anchors: [batch, num_anchors, (y1, x1, y2, x2)] anchors in normalized coordinates Returns: Proposals in normalized coordinates [batch, rois, (y1, x1, y2, x2)] """ def __init__(self, proposal_count, nms_threshold, config=None, **kwargs): super(ProposalLayer, self).__init__(**kwargs) self.config = config self.proposal_count = proposal_count self.nms_threshold = nms_threshold def call(self, inputs): # Box Scores. Use the foreground class confidence. [Batch, num_rois, 1] scores = inputs[0][:, :, 1] # Box deltas [batch, num_rois, 4] deltas = inputs[1] deltas = deltas * np.reshape(self.config.RPN_BBOX_STD_DEV, [1, 1, 4]) # Anchors anchors = inputs[2] # Improve performance by trimming to top anchors by score # and doing the rest on the smaller subset. pre_nms_limit = tf.minimum(self.config.PRE_NMS_LIMIT, tf.shape(anchors)[1]) ix = tf.nn.top_k(scores, pre_nms_limit, sorted=True, name="top_anchors").indices scores = utils.batch_slice([scores, ix], lambda x, y: tf.gather(x, y), self.config.IMAGES_PER_GPU) deltas = utils.batch_slice([deltas, ix], lambda x, y: tf.gather(x, y), self.config.IMAGES_PER_GPU) pre_nms_anchors = utils.batch_slice([anchors, ix], lambda a, x: tf.gather(a, x), self.config.IMAGES_PER_GPU, names=["pre_nms_anchors"]) # Apply deltas to anchors to get refined anchors. # [batch, N, (y1, x1, y2, x2)] boxes = utils.batch_slice([pre_nms_anchors, deltas], lambda x, y: apply_box_deltas_graph(x, y), self.config.IMAGES_PER_GPU, names=["refined_anchors"]) # Clip to image boundaries. Since we're in normalized coordinates, # clip to 0..1 range. [batch, N, (y1, x1, y2, x2)] window = np.array([0, 0, 1, 1], dtype=np.float32) boxes = utils.batch_slice(boxes, lambda x: clip_boxes_graph(x, window), self.config.IMAGES_PER_GPU, names=["refined_anchors_clipped"]) # Filter out small boxes # According to Xinlei Chen's paper, this reduces detection accuracy # for small objects, so we're skipping it. # Non-max suppression def nms(boxes, scores): indices = tf.image.non_max_suppression( boxes, scores, self.proposal_count, self.nms_threshold, name="rpn_non_max_suppression") proposals = tf.gather(boxes, indices) # Pad if needed padding = tf.maximum(self.proposal_count - tf.shape(proposals)[0], 0) proposals = tf.pad(proposals, [(0, padding), (0, 0)]) return proposals proposals = utils.batch_slice([boxes, scores], nms, self.config.IMAGES_PER_GPU) return proposals def compute_output_shape(self, input_shape): return (None, self.proposal_count, 4) ############################################################ # ROIAlign Layer ############################################################ def log2_graph(x): """Implementation of Log2. TF doesn't have a native implementation.""" return tf.log(x) / tf.log(2.0) class PyramidROIAlign(KE.Layer): """Implements ROI Pooling on multiple levels of the feature pyramid. Params: - pool_shape: [pool_height, pool_width] of the output pooled regions. Usually [7, 7] Inputs: - boxes: [batch, num_boxes, (y1, x1, y2, x2)] in normalized coordinates. Possibly padded with zeros if not enough boxes to fill the array. - image_meta: [batch, (meta data)] Image details. See compose_image_meta() - feature_maps: List of feature maps from different levels of the pyramid. Each is [batch, height, width, channels] Output: Pooled regions in the shape: [batch, num_boxes, pool_height, pool_width, channels]. The width and height are those specific in the pool_shape in the layer constructor. """ def __init__(self, pool_shape, **kwargs): super(PyramidROIAlign, self).__init__(**kwargs) self.pool_shape = tuple(pool_shape) def call(self, inputs): # Crop boxes [batch, num_boxes, (y1, x1, y2, x2)] in normalized coords boxes = inputs[0] # Image meta # Holds details about the image. See compose_image_meta() image_meta = inputs[1] # Feature Maps. List of feature maps from different level of the # feature pyramid. Each is [batch, height, width, channels] feature_maps = inputs[2:] # Assign each ROI to a level in the pyramid based on the ROI area. y1, x1, y2, x2 = tf.split(boxes, 4, axis=2) h = y2 - y1 w = x2 - x1 # Use shape of first image. Images in a batch must have the same size. image_shape = parse_image_meta_graph(image_meta)['image_shape'][0] # Equation 1 in the Feature Pyramid Networks paper. Account for # the fact that our coordinates are normalized here. # e.g. a 224x224 ROI (in pixels) maps to P4 image_area = tf.cast(image_shape[0] * image_shape[1], tf.float32) roi_level = log2_graph(tf.sqrt(h * w) / (224.0 / tf.sqrt(image_area))) roi_level = tf.minimum(5, tf.maximum( 2, 4 + tf.cast(tf.round(roi_level), tf.int32))) roi_level = tf.squeeze(roi_level, 2) # Loop through levels and apply ROI pooling to each. P2 to P5. pooled = [] box_to_level = [] for i, level in enumerate(range(2, 6)): ix = tf.where(tf.equal(roi_level, level)) level_boxes = tf.gather_nd(boxes, ix) # Box indices for crop_and_resize. box_indices = tf.cast(ix[:, 0], tf.int32) # Keep track of which box is mapped to which level box_to_level.append(ix) # Stop gradient propogation to ROI proposals level_boxes = tf.stop_gradient(level_boxes) box_indices = tf.stop_gradient(box_indices) # Crop and Resize # From Mask R-CNN paper: "We sample four regular locations, so # that we can evaluate either max or average pooling. In fact, # interpolating only a single value at each bin center (without # pooling) is nearly as effective." # # Here we use the simplified approach of a single value per bin, # which is how it's done in tf.crop_and_resize() # Result: [batch * num_boxes, pool_height, pool_width, channels] pooled.append(tf.image.crop_and_resize( feature_maps[i], level_boxes, box_indices, self.pool_shape, method="bilinear")) # Pack pooled features into one tensor pooled = tf.concat(pooled, axis=0) # Pack box_to_level mapping into one array and add another # column representing the order of pooled boxes box_to_level = tf.concat(box_to_level, axis=0) box_range = tf.expand_dims(tf.range(tf.shape(box_to_level)[0]), 1) box_to_level = tf.concat([tf.cast(box_to_level, tf.int32), box_range], axis=1) # Rearrange pooled features to match the order of the original boxes # Sort box_to_level by batch then box index # TF doesn't have a way to sort by two columns, so merge them and sort. sorting_tensor = box_to_level[:, 0] * 100000 + box_to_level[:, 1] ix = tf.nn.top_k(sorting_tensor, k=tf.shape( box_to_level)[0]).indices[::-1] ix = tf.gather(box_to_level[:, 2], ix) pooled = tf.gather(pooled, ix) # Re-add the batch dimension shape = tf.concat([tf.shape(boxes)[:2], tf.shape(pooled)[1:]], axis=0) pooled = tf.reshape(pooled, shape) return pooled def compute_output_shape(self, input_shape): return input_shape[0][:2] + self.pool_shape + (input_shape[2][-1], ) ############################################################ # Detection Target Layer ############################################################ def overlaps_graph(boxes1, boxes2): """Computes IoU overlaps between two sets of boxes. boxes1, boxes2: [N, (y1, x1, y2, x2)]. """ # 1. Tile boxes2 and repeat boxes1. This allows us to compare # every boxes1 against every boxes2 without loops. # TF doesn't have an equivalent to np.repeat() so simulate it # using tf.tile() and tf.reshape. b1 = tf.reshape(tf.tile(tf.expand_dims(boxes1, 1), [1, 1, tf.shape(boxes2)[0]]), [-1, 4]) b2 = tf.tile(boxes2, [tf.shape(boxes1)[0], 1]) # 2. Compute intersections b1_y1, b1_x1, b1_y2, b1_x2 = tf.split(b1, 4, axis=1) b2_y1, b2_x1, b2_y2, b2_x2 = tf.split(b2, 4, axis=1) y1 = tf.maximum(b1_y1, b2_y1) x1 = tf.maximum(b1_x1, b2_x1) y2 = tf.minimum(b1_y2, b2_y2) x2 = tf.minimum(b1_x2, b2_x2) intersection = tf.maximum(x2 - x1, 0) * tf.maximum(y2 - y1, 0) # 3. Compute unions b1_area = (b1_y2 - b1_y1) * (b1_x2 - b1_x1) b2_area = (b2_y2 - b2_y1) * (b2_x2 - b2_x1) union = b1_area + b2_area - intersection # 4. Compute IoU and reshape to [boxes1, boxes2] iou = intersection / union overlaps = tf.reshape(iou, [tf.shape(boxes1)[0], tf.shape(boxes2)[0]]) return overlaps def detection_targets_graph(proposals, gt_class_ids, gt_boxes, gt_masks, config): """Generates detection targets for one image. Subsamples proposals and generates target class IDs, bounding box deltas, and masks for each. Inputs: proposals: [POST_NMS_ROIS_TRAINING, (y1, x1, y2, x2)] in normalized coordinates. Might be zero padded if there are not enough proposals. gt_class_ids: [MAX_GT_INSTANCES] int class IDs gt_boxes: [MAX_GT_INSTANCES, (y1, x1, y2, x2)] in normalized coordinates. gt_masks: [height, width, MAX_GT_INSTANCES] of boolean type. Returns: Target ROIs and corresponding class IDs, bounding box shifts, and masks. rois: [TRAIN_ROIS_PER_IMAGE, (y1, x1, y2, x2)] in normalized coordinates class_ids: [TRAIN_ROIS_PER_IMAGE]. Integer class IDs. Zero padded. deltas: [TRAIN_ROIS_PER_IMAGE, (dy, dx, log(dh), log(dw))] masks: [TRAIN_ROIS_PER_IMAGE, height, width]. Masks cropped to bbox boundaries and resized to neural network output size. Note: Returned arrays might be zero padded if not enough target ROIs. """ # Assertions asserts = [ tf.Assert(tf.greater(tf.shape(proposals)[0], 0), [proposals], name="roi_assertion"), ] with tf.control_dependencies(asserts): proposals = tf.identity(proposals) # Remove zero padding proposals, _ = trim_zeros_graph(proposals, name="trim_proposals") gt_boxes, non_zeros = trim_zeros_graph(gt_boxes, name="trim_gt_boxes") gt_class_ids = tf.boolean_mask(gt_class_ids, non_zeros, name="trim_gt_class_ids") gt_masks = tf.gather(gt_masks, tf.where(non_zeros)[:, 0], axis=2, name="trim_gt_masks") # Handle COCO crowds # A crowd box in COCO is a bounding box around several instances. Exclude # them from training. A crowd box is given a negative class ID. crowd_ix = tf.where(gt_class_ids < 0)[:, 0] non_crowd_ix = tf.where(gt_class_ids > 0)[:, 0] crowd_boxes = tf.gather(gt_boxes, crowd_ix) crowd_masks = tf.gather(gt_masks, crowd_ix, axis=2) gt_class_ids = tf.gather(gt_class_ids, non_crowd_ix) gt_boxes = tf.gather(gt_boxes, non_crowd_ix) gt_masks = tf.gather(gt_masks, non_crowd_ix, axis=2) # Compute overlaps matrix [proposals, gt_boxes] overlaps = overlaps_graph(proposals, gt_boxes) # Compute overlaps with crowd boxes [proposals, crowd_boxes] crowd_overlaps = overlaps_graph(proposals, crowd_boxes) crowd_iou_max = tf.reduce_max(crowd_overlaps, axis=1) no_crowd_bool = (crowd_iou_max < 0.001) # Determine positive and negative ROIs roi_iou_max = tf.reduce_max(overlaps, axis=1) # 1. Positive ROIs are those with >= 0.5 IoU with a GT box positive_roi_bool = (roi_iou_max >= 0.5) positive_indices = tf.where(positive_roi_bool)[:, 0] # 2. Negative ROIs are those with < 0.5 with every GT box. Skip crowds. negative_indices = tf.where(tf.logical_and(roi_iou_max < 0.5, no_crowd_bool))[:, 0] # Subsample ROIs. Aim for 33% positive # Positive ROIs positive_count = int(config.TRAIN_ROIS_PER_IMAGE * config.ROI_POSITIVE_RATIO) positive_indices = tf.random_shuffle(positive_indices)[:positive_count] positive_count = tf.shape(positive_indices)[0] # Negative ROIs. Add enough to maintain positive:negative ratio. r = 1.0 / config.ROI_POSITIVE_RATIO negative_count = tf.cast(r * tf.cast(positive_count, tf.float32), tf.int32) - positive_count negative_indices = tf.random_shuffle(negative_indices)[:negative_count] # Gather selected ROIs positive_rois = tf.gather(proposals, positive_indices) negative_rois = tf.gather(proposals, negative_indices) # Assign positive ROIs to GT boxes. positive_overlaps = tf.gather(overlaps, positive_indices) roi_gt_box_assignment = tf.cond( tf.greater(tf.shape(positive_overlaps)[1], 0), true_fn = lambda: tf.argmax(positive_overlaps, axis=1), false_fn = lambda: tf.cast(tf.constant([]),tf.int64) ) roi_gt_boxes = tf.gather(gt_boxes, roi_gt_box_assignment) roi_gt_class_ids = tf.gather(gt_class_ids, roi_gt_box_assignment) # Compute bbox refinement for positive ROIs deltas = utils.box_refinement_graph(positive_rois, roi_gt_boxes) deltas /= config.BBOX_STD_DEV # Assign positive ROIs to GT masks # Permute masks to [N, height, width, 1] transposed_masks = tf.expand_dims(tf.transpose(gt_masks, [2, 0, 1]), -1) # Pick the right mask for each ROI roi_masks = tf.gather(transposed_masks, roi_gt_box_assignment) # Compute mask targets boxes = positive_rois if config.USE_MINI_MASK: # Transform ROI coordinates from normalized image space # to normalized mini-mask space. y1, x1, y2, x2 = tf.split(positive_rois, 4, axis=1) gt_y1, gt_x1, gt_y2, gt_x2 = tf.split(roi_gt_boxes, 4, axis=1) gt_h = gt_y2 - gt_y1 gt_w = gt_x2 - gt_x1 y1 = (y1 - gt_y1) / gt_h x1 = (x1 - gt_x1) / gt_w y2 = (y2 - gt_y1) / gt_h x2 = (x2 - gt_x1) / gt_w boxes = tf.concat([y1, x1, y2, x2], 1) box_ids = tf.range(0, tf.shape(roi_masks)[0]) masks = tf.image.crop_and_resize(tf.cast(roi_masks, tf.float32), boxes, box_ids, config.MASK_SHAPE) # Remove the extra dimension from masks. masks = tf.squeeze(masks, axis=3) # Threshold mask pixels at 0.5 to have GT masks be 0 or 1 to use with # binary cross entropy loss. masks = tf.round(masks) # Append negative ROIs and pad bbox deltas and masks that # are not used for negative ROIs with zeros. rois = tf.concat([positive_rois, negative_rois], axis=0) N = tf.shape(negative_rois)[0] P = tf.maximum(config.TRAIN_ROIS_PER_IMAGE - tf.shape(rois)[0], 0) rois = tf.pad(rois, [(0, P), (0, 0)]) roi_gt_boxes = tf.pad(roi_gt_boxes, [(0, N + P), (0, 0)]) roi_gt_class_ids = tf.pad(roi_gt_class_ids, [(0, N + P)]) deltas = tf.pad(deltas, [(0, N + P), (0, 0)]) masks = tf.pad(masks, [[0, N + P], (0, 0), (0, 0)]) return rois, roi_gt_class_ids, deltas, masks class DetectionTargetLayer(KE.Layer): """Subsamples proposals and generates target box refinement, class_ids, and masks for each. Inputs: proposals: [batch, N, (y1, x1, y2, x2)] in normalized coordinates. Might be zero padded if there are not enough proposals. gt_class_ids: [batch, MAX_GT_INSTANCES] Integer class IDs. gt_boxes: [batch, MAX_GT_INSTANCES, (y1, x1, y2, x2)] in normalized coordinates. gt_masks: [batch, height, width, MAX_GT_INSTANCES] of boolean type Returns: Target ROIs and corresponding class IDs, bounding box shifts, and masks. rois: [batch, TRAIN_ROIS_PER_IMAGE, (y1, x1, y2, x2)] in normalized coordinates target_class_ids: [batch, TRAIN_ROIS_PER_IMAGE]. Integer class IDs. target_deltas: [batch, TRAIN_ROIS_PER_IMAGE, (dy, dx, log(dh), log(dw)] target_mask: [batch, TRAIN_ROIS_PER_IMAGE, height, width] Masks cropped to bbox boundaries and resized to neural network output size. Note: Returned arrays might be zero padded if not enough target ROIs. """ def __init__(self, config, **kwargs): super(DetectionTargetLayer, self).__init__(**kwargs) self.config = config def call(self, inputs): proposals = inputs[0] gt_class_ids = inputs[1] gt_boxes = inputs[2] gt_masks = inputs[3] # Slice the batch and run a graph for each slice # TODO: Rename target_bbox to target_deltas for clarity names = ["rois", "target_class_ids", "target_bbox", "target_mask"] outputs = utils.batch_slice( [proposals, gt_class_ids, gt_boxes, gt_masks], lambda w, x, y, z: detection_targets_graph( w, x, y, z, self.config), self.config.IMAGES_PER_GPU, names=names) return outputs def compute_output_shape(self, input_shape): return [ (None, self.config.TRAIN_ROIS_PER_IMAGE, 4), # rois (None, self.config.TRAIN_ROIS_PER_IMAGE), # class_ids (None, self.config.TRAIN_ROIS_PER_IMAGE, 4), # deltas (None, self.config.TRAIN_ROIS_PER_IMAGE, self.config.MASK_SHAPE[0], self.config.MASK_SHAPE[1]) # masks ] def compute_mask(self, inputs, mask=None): return [None, None, None, None] ############################################################ # Detection Layer ############################################################ def refine_detections_graph(rois, probs, deltas, window, config): """Refine classified proposals and filter overlaps and return final detections. Inputs: rois: [N, (y1, x1, y2, x2)] in normalized coordinates probs: [N, num_classes]. Class probabilities. deltas: [N, num_classes, (dy, dx, log(dh), log(dw))]. Class-specific bounding box deltas. window: (y1, x1, y2, x2) in normalized coordinates. The part of the image that contains the image excluding the padding. Returns detections shaped: [num_detections, (y1, x1, y2, x2, class_id, score)] where coordinates are normalized. """ # Class IDs per ROI class_ids = tf.argmax(probs, axis=1, output_type=tf.int32) # Class probability of the top class of each ROI indices = tf.stack([tf.range(probs.shape[0]), class_ids], axis=1) class_scores = tf.gather_nd(probs, indices) # Class-specific bounding box deltas deltas_specific = tf.gather_nd(deltas, indices) # Apply bounding box deltas # Shape: [boxes, (y1, x1, y2, x2)] in normalized coordinates refined_rois = apply_box_deltas_graph( rois, deltas_specific * config.BBOX_STD_DEV) # Clip boxes to image window refined_rois = clip_boxes_graph(refined_rois, window) # TODO: Filter out boxes with zero area # Filter out background boxes keep = tf.where(class_ids > 0)[:, 0] # Filter out low confidence boxes if config.DETECTION_MIN_CONFIDENCE: conf_keep = tf.where(class_scores >= config.DETECTION_MIN_CONFIDENCE)[:, 0] keep = tf.sets.set_intersection(tf.expand_dims(keep, 0), tf.expand_dims(conf_keep, 0)) keep = tf.sparse_tensor_to_dense(keep)[0] # Apply per-class NMS # 1. Prepare variables pre_nms_class_ids = tf.gather(class_ids, keep) pre_nms_scores = tf.gather(class_scores, keep) pre_nms_rois = tf.gather(refined_rois, keep) unique_pre_nms_class_ids = tf.unique(pre_nms_class_ids)[0] def nms_keep_map(class_id): """Apply Non-Maximum Suppression on ROIs of the given class.""" # Indices of ROIs of the given class ixs = tf.where(tf.equal(pre_nms_class_ids, class_id))[:, 0] # Apply NMS class_keep = tf.image.non_max_suppression( tf.gather(pre_nms_rois, ixs), tf.gather(pre_nms_scores, ixs), max_output_size=config.DETECTION_MAX_INSTANCES, iou_threshold=config.DETECTION_NMS_THRESHOLD) # Map indices class_keep = tf.gather(keep, tf.gather(ixs, class_keep)) # Pad with -1 so returned tensors have the same shape gap = config.DETECTION_MAX_INSTANCES - tf.shape(class_keep)[0] class_keep = tf.pad(class_keep, [(0, gap)], mode='CONSTANT', constant_values=-1) # Set shape so map_fn() can infer result shape class_keep.set_shape([config.DETECTION_MAX_INSTANCES]) return class_keep # 2. Map over class IDs nms_keep = tf.map_fn(nms_keep_map, unique_pre_nms_class_ids, dtype=tf.int64) # 3. Merge results into one list, and remove -1 padding nms_keep = tf.reshape(nms_keep, [-1]) nms_keep = tf.gather(nms_keep, tf.where(nms_keep > -1)[:, 0]) # 4. Compute intersection between keep and nms_keep keep = tf.sets.set_intersection(tf.expand_dims(keep, 0), tf.expand_dims(nms_keep, 0)) keep = tf.sparse_tensor_to_dense(keep)[0] # Keep top detections roi_count = config.DETECTION_MAX_INSTANCES class_scores_keep = tf.gather(class_scores, keep) num_keep = tf.minimum(tf.shape(class_scores_keep)[0], roi_count) top_ids = tf.nn.top_k(class_scores_keep, k=num_keep, sorted=True)[1] keep = tf.gather(keep, top_ids) # Arrange output as [N, (y1, x1, y2, x2, class_id, score)] # Coordinates are normalized. detections = tf.concat([ tf.gather(refined_rois, keep), tf.to_float(tf.gather(class_ids, keep))[..., tf.newaxis], tf.gather(class_scores, keep)[..., tf.newaxis] ], axis=1) # Pad with zeros if detections < DETECTION_MAX_INSTANCES gap = config.DETECTION_MAX_INSTANCES - tf.shape(detections)[0] detections = tf.pad(detections, [(0, gap), (0, 0)], "CONSTANT") return detections class DetectionLayer(KE.Layer): """Takes classified proposal boxes and their bounding box deltas and returns the final detection boxes. Returns: [batch, num_detections, (y1, x1, y2, x2, class_id, class_score)] where coordinates are normalized. """ def __init__(self, config=None, **kwargs): super(DetectionLayer, self).__init__(**kwargs) self.config = config def call(self, inputs): rois = inputs[0] mrcnn_class = inputs[1] mrcnn_bbox = inputs[2] image_meta = inputs[3] # Get windows of images in normalized coordinates. Windows are the area # in the image that excludes the padding. # Use the shape of the first image in the batch to normalize the window # because we know that all images get resized to the same size. m = parse_image_meta_graph(image_meta) image_shape = m['image_shape'][0] window = norm_boxes_graph(m['window'], image_shape[:2]) # Run detection refinement graph on each item in the batch detections_batch = utils.batch_slice( [rois, mrcnn_class, mrcnn_bbox, window], lambda x, y, w, z: refine_detections_graph(x, y, w, z, self.config), self.config.IMAGES_PER_GPU) # Reshape output # [batch, num_detections, (y1, x1, y2, x2, class_id, class_score)] in # normalized coordinates return tf.reshape( detections_batch, [self.config.BATCH_SIZE, self.config.DETECTION_MAX_INSTANCES, 6]) def compute_output_shape(self, input_shape): return (None, self.config.DETECTION_MAX_INSTANCES, 6) ############################################################ # Region Proposal Network (RPN) ############################################################ def rpn_graph(feature_map, anchors_per_location, anchor_stride): """Builds the computation graph of Region Proposal Network. feature_map: backbone features [batch, height, width, depth] anchors_per_location: number of anchors per pixel in the feature map anchor_stride: Controls the density of anchors. Typically 1 (anchors for every pixel in the feature map), or 2 (every other pixel). Returns: rpn_class_logits: [batch, H * W * anchors_per_location, 2] Anchor classifier logits (before softmax) rpn_probs: [batch, H * W * anchors_per_location, 2] Anchor classifier probabilities. rpn_bbox: [batch, H * W * anchors_per_location, (dy, dx, log(dh), log(dw))] Deltas to be applied to anchors. """ # TODO: check if stride of 2 causes alignment issues if the feature map # is not even. # Shared convolutional base of the RPN shared = KL.Conv2D(512, (3, 3), padding='same', activation='relu', strides=anchor_stride, name='rpn_conv_shared')(feature_map) # Anchor Score. [batch, height, width, anchors per location * 2]. x = KL.Conv2D(2 * anchors_per_location, (1, 1), padding='valid', activation='linear', name='rpn_class_raw')(shared) # Reshape to [batch, anchors, 2] rpn_class_logits = KL.Lambda( lambda t: tf.reshape(t, [tf.shape(t)[0], -1, 2]))(x) # Softmax on last dimension of BG/FG. rpn_probs = KL.Activation( "softmax", name="rpn_class_xxx")(rpn_class_logits) # Bounding box refinement. [batch, H, W, anchors per location * depth] # where depth is [x, y, log(w), log(h)] x = KL.Conv2D(anchors_per_location * 4, (1, 1), padding="valid", activation='linear', name='rpn_bbox_pred')(shared) # Reshape to [batch, anchors, 4] rpn_bbox = KL.Lambda(lambda t: tf.reshape(t, [tf.shape(t)[0], -1, 4]))(x) return [rpn_class_logits, rpn_probs, rpn_bbox] def build_rpn_model(anchor_stride, anchors_per_location, depth): """Builds a Keras model of the Region Proposal Network. It wraps the RPN graph so it can be used multiple times with shared weights. anchors_per_location: number of anchors per pixel in the feature map anchor_stride: Controls the density of anchors. Typically 1 (anchors for every pixel in the feature map), or 2 (every other pixel). depth: Depth of the backbone feature map. Returns a Keras Model object. The model outputs, when called, are: rpn_class_logits: [batch, H * W * anchors_per_location, 2] Anchor classifier logits (before softmax) rpn_probs: [batch, H * W * anchors_per_location, 2] Anchor classifier probabilities. rpn_bbox: [batch, H * W * anchors_per_location, (dy, dx, log(dh), log(dw))] Deltas to be applied to anchors. """ input_feature_map = KL.Input(shape=[None, None, depth], name="input_rpn_feature_map") outputs = rpn_graph(input_feature_map, anchors_per_location, anchor_stride) return KM.Model([input_feature_map], outputs, name="rpn_model") ############################################################ # Feature Pyramid Network Heads ############################################################ def fpn_classifier_graph(rois, feature_maps, image_meta, pool_size, num_classes, train_bn=True, fc_layers_size=1024): """Builds the computation graph of the feature pyramid network classifier and regressor heads. rois: [batch, num_rois, (y1, x1, y2, x2)] Proposal boxes in normalized coordinates. feature_maps: List of feature maps from different layers of the pyramid, [P2, P3, P4, P5]. Each has a different resolution. image_meta: [batch, (meta data)] Image details. See compose_image_meta() pool_size: The width of the square feature map generated from ROI Pooling. num_classes: number of classes, which determines the depth of the results train_bn: Boolean. Train or freeze Batch Norm layers fc_layers_size: Size of the 2 FC layers Returns: logits: [batch, num_rois, NUM_CLASSES] classifier logits (before softmax) probs: [batch, num_rois, NUM_CLASSES] classifier probabilities bbox_deltas: [batch, num_rois, NUM_CLASSES, (dy, dx, log(dh), log(dw))] Deltas to apply to proposal boxes """ # ROI Pooling # Shape: [batch, num_rois, POOL_SIZE, POOL_SIZE, channels] x = PyramidROIAlign([pool_size, pool_size], name="roi_align_classifier")([rois, image_meta] + feature_maps) # Two 1024 FC layers (implemented with Conv2D for consistency) x = KL.TimeDistributed(KL.Conv2D(fc_layers_size, (pool_size, pool_size), padding="valid"), name="mrcnn_class_conv1")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_class_bn1')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.TimeDistributed(KL.Conv2D(fc_layers_size, (1, 1)), name="mrcnn_class_conv2")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_class_bn2')(x, training=train_bn) x = KL.Activation('relu')(x) shared = KL.Lambda(lambda x: K.squeeze(K.squeeze(x, 3), 2), name="pool_squeeze")(x) # Classifier head mrcnn_class_logits = KL.TimeDistributed(KL.Dense(num_classes), name='mrcnn_class_logits')(shared) mrcnn_probs = KL.TimeDistributed(KL.Activation("softmax"), name="mrcnn_class")(mrcnn_class_logits) # BBox head # [batch, num_rois, NUM_CLASSES * (dy, dx, log(dh), log(dw))] x = KL.TimeDistributed(KL.Dense(num_classes * 4, activation='linear'), name='mrcnn_bbox_fc')(shared) # Reshape to [batch, num_rois, NUM_CLASSES, (dy, dx, log(dh), log(dw))] s = K.int_shape(x) mrcnn_bbox = KL.Reshape((s[1], num_classes, 4), name="mrcnn_bbox")(x) return mrcnn_class_logits, mrcnn_probs, mrcnn_bbox def build_fpn_mask_graph(rois, feature_maps, image_meta, pool_size, num_classes, train_bn=True): """Builds the computation graph of the mask head of Feature Pyramid Network. rois: [batch, num_rois, (y1, x1, y2, x2)] Proposal boxes in normalized coordinates. feature_maps: List of feature maps from different layers of the pyramid, [P2, P3, P4, P5]. Each has a different resolution. image_meta: [batch, (meta data)] Image details. See compose_image_meta() pool_size: The width of the square feature map generated from ROI Pooling. num_classes: number of classes, which determines the depth of the results train_bn: Boolean. Train or freeze Batch Norm layers Returns: Masks [batch, num_rois, MASK_POOL_SIZE, MASK_POOL_SIZE, NUM_CLASSES] """ # ROI Pooling # Shape: [batch, num_rois, MASK_POOL_SIZE, MASK_POOL_SIZE, channels] x = PyramidROIAlign([pool_size, pool_size], name="roi_align_mask")([rois, image_meta] + feature_maps) # Conv layers x = KL.TimeDistributed(KL.Conv2D(256, (3, 3), padding="same"), name="mrcnn_mask_conv1")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_mask_bn1')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.TimeDistributed(KL.Conv2D(256, (3, 3), padding="same"), name="mrcnn_mask_conv2")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_mask_bn2')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.TimeDistributed(KL.Conv2D(256, (3, 3), padding="same"), name="mrcnn_mask_conv3")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_mask_bn3')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.TimeDistributed(KL.Conv2D(256, (3, 3), padding="same"), name="mrcnn_mask_conv4")(x) x = KL.TimeDistributed(BatchNorm(), name='mrcnn_mask_bn4')(x, training=train_bn) x = KL.Activation('relu')(x) x = KL.TimeDistributed(KL.Conv2DTranspose(256, (2, 2), strides=2, activation="relu"), name="mrcnn_mask_deconv")(x) x = KL.TimeDistributed(KL.Conv2D(num_classes, (1, 1), strides=1, activation="sigmoid"), name="mrcnn_mask")(x) return x ############################################################ # Loss Functions ############################################################ def smooth_l1_loss(y_true, y_pred): """Implements Smooth-L1 loss. y_true and y_pred are typically: [N, 4], but could be any shape. """ diff = K.abs(y_true - y_pred) less_than_one = K.cast(K.less(diff, 1.0), "float32") loss = (less_than_one * 0.5 * diff**2) + (1 - less_than_one) * (diff - 0.5) return loss def rpn_class_loss_graph(rpn_match, rpn_class_logits): """RPN anchor classifier loss. rpn_match: [batch, anchors, 1]. Anchor match type. 1=positive, -1=negative, 0=neutral anchor. rpn_class_logits: [batch, anchors, 2]. RPN classifier logits for FG/BG. """ # Squeeze last dim to simplify rpn_match = tf.squeeze(rpn_match, -1) # Get anchor classes. Convert the -1/+1 match to 0/1 values. anchor_class = K.cast(K.equal(rpn_match, 1), tf.int32) # Positive and Negative anchors contribute to the loss, # but neutral anchors (match value = 0) don't. indices = tf.where(K.not_equal(rpn_match, 0)) # Pick rows that contribute to the loss and filter out the rest. rpn_class_logits = tf.gather_nd(rpn_class_logits, indices) anchor_class = tf.gather_nd(anchor_class, indices) # Cross entropy loss loss = K.sparse_categorical_crossentropy(target=anchor_class, output=rpn_class_logits, from_logits=True) loss = K.switch(tf.size(loss) > 0, K.mean(loss), tf.constant(0.0)) return loss def rpn_bbox_loss_graph(config, target_bbox, rpn_match, rpn_bbox): """Return the RPN bounding box loss graph. config: the model config object. target_bbox: [batch, max positive anchors, (dy, dx, log(dh), log(dw))]. Uses 0 padding to fill in unsed bbox deltas. rpn_match: [batch, anchors, 1]. Anchor match type. 1=positive, -1=negative, 0=neutral anchor. rpn_bbox: [batch, anchors, (dy, dx, log(dh), log(dw))] """ # Positive anchors contribute to the loss, but negative and # neutral anchors (match value of 0 or -1) don't. rpn_match = K.squeeze(rpn_match, -1) indices = tf.where(K.equal(rpn_match, 1)) # Pick bbox deltas that contribute to the loss rpn_bbox = tf.gather_nd(rpn_bbox, indices) # Trim target bounding box deltas to the same length as rpn_bbox. batch_counts = K.sum(K.cast(K.equal(rpn_match, 1), tf.int32), axis=1) target_bbox = batch_pack_graph(target_bbox, batch_counts, config.IMAGES_PER_GPU) loss = smooth_l1_loss(target_bbox, rpn_bbox) loss = K.switch(tf.size(loss) > 0, K.mean(loss), tf.constant(0.0)) return loss def mrcnn_class_loss_graph(target_class_ids, pred_class_logits, active_class_ids): """Loss for the classifier head of Mask RCNN. target_class_ids: [batch, num_rois]. Integer class IDs. Uses zero padding to fill in the array. pred_class_logits: [batch, num_rois, num_classes] active_class_ids: [batch, num_classes]. Has a value of 1 for classes that are in the dataset of the image, and 0 for classes that are not in the dataset. """ # During model building, Keras calls this function with # target_class_ids of type float32. Unclear why. Cast it # to int to get around it. target_class_ids = tf.cast(target_class_ids, 'int64') # Find predictions of classes that are not in the dataset. pred_class_ids = tf.argmax(pred_class_logits, axis=2) # TODO: Update this line to work with batch > 1. Right now it assumes all # images in a batch have the same active_class_ids pred_active = tf.gather(active_class_ids[0], pred_class_ids) # Loss loss = tf.nn.sparse_softmax_cross_entropy_with_logits( labels=target_class_ids, logits=pred_class_logits) # Erase losses of predictions of classes that are not in the active # classes of the image. loss = loss * pred_active # Computer loss mean. Use only predictions that contribute # to the loss to get a correct mean. loss = tf.reduce_sum(loss) / tf.reduce_sum(pred_active) return loss def mrcnn_bbox_loss_graph(target_bbox, target_class_ids, pred_bbox): """Loss for Mask R-CNN bounding box refinement. target_bbox: [batch, num_rois, (dy, dx, log(dh), log(dw))] target_class_ids: [batch, num_rois]. Integer class IDs. pred_bbox: [batch, num_rois, num_classes, (dy, dx, log(dh), log(dw))] """ # Reshape to merge batch and roi dimensions for simplicity. target_class_ids = K.reshape(target_class_ids, (-1,)) target_bbox = K.reshape(target_bbox, (-1, 4)) pred_bbox = K.reshape(pred_bbox, (-1, K.int_shape(pred_bbox)[2], 4)) # Only positive ROIs contribute to the loss. And only # the right class_id of each ROI. Get their indices. positive_roi_ix = tf.where(target_class_ids > 0)[:, 0] positive_roi_class_ids = tf.cast( tf.gather(target_class_ids, positive_roi_ix), tf.int64) indices = tf.stack([positive_roi_ix, positive_roi_class_ids], axis=1) # Gather the deltas (predicted and true) that contribute to loss target_bbox = tf.gather(target_bbox, positive_roi_ix) pred_bbox = tf.gather_nd(pred_bbox, indices) # Smooth-L1 Loss loss = K.switch(tf.size(target_bbox) > 0, smooth_l1_loss(y_true=target_bbox, y_pred=pred_bbox), tf.constant(0.0)) loss = K.mean(loss) return loss def mrcnn_mask_loss_graph(target_masks, target_class_ids, pred_masks): """Mask binary cross-entropy loss for the masks head. target_masks: [batch, num_rois, height, width]. A float32 tensor of values 0 or 1. Uses zero padding to fill array. target_class_ids: [batch, num_rois]. Integer class IDs. Zero padded. pred_masks: [batch, proposals, height, width, num_classes] float32 tensor with values from 0 to 1. """ # Reshape for simplicity. Merge first two dimensions into one. target_class_ids = K.reshape(target_class_ids, (-1,)) mask_shape = tf.shape(target_masks) target_masks = K.reshape(target_masks, (-1, mask_shape[2], mask_shape[3])) pred_shape = tf.shape(pred_masks) pred_masks = K.reshape(pred_masks, (-1, pred_shape[2], pred_shape[3], pred_shape[4])) # Permute predicted masks to [N, num_classes, height, width] pred_masks = tf.transpose(pred_masks, [0, 3, 1, 2]) # Only positive ROIs contribute to the loss. And only # the class specific mask of each ROI. positive_ix = tf.where(target_class_ids > 0)[:, 0] positive_class_ids = tf.cast( tf.gather(target_class_ids, positive_ix), tf.int64) indices = tf.stack([positive_ix, positive_class_ids], axis=1) # Gather the masks (predicted and true) that contribute to loss y_true = tf.gather(target_masks, positive_ix) y_pred = tf.gather_nd(pred_masks, indices) # Compute binary cross entropy. If no positive ROIs, then return 0. # shape: [batch, roi, num_classes] loss = K.switch(tf.size(y_true) > 0, K.binary_crossentropy(target=y_true, output=y_pred), tf.constant(0.0)) loss = K.mean(loss) return loss ############################################################ # Data Generator ############################################################ def load_image_gt(dataset, config, image_id, augment=False, augmentation=None, use_mini_mask=False): """Load and return ground truth data for an image (image, mask, bounding boxes). augment: (deprecated. Use augmentation instead). If true, apply random image augmentation. Currently, only horizontal flipping is offered. augmentation: Optional. An imgaug (https://github.com/aleju/imgaug) augmentation. For example, passing imgaug.augmenters.Fliplr(0.5) flips images right/left 50% of the time. use_mini_mask: If False, returns full-size masks that are the same height and width as the original image. These can be big, for example 1024x1024x100 (for 100 instances). Mini masks are smaller, typically, 224x224 and are generated by extracting the bounding box of the object and resizing it to MINI_MASK_SHAPE. Returns: image: [height, width, 3] shape: the original shape of the image before resizing and cropping. class_ids: [instance_count] Integer class IDs bbox: [instance_count, (y1, x1, y2, x2)] mask: [height, width, instance_count]. The height and width are those of the image unless use_mini_mask is True, in which case they are defined in MINI_MASK_SHAPE. """ # Load image and mask image = dataset.load_image(image_id) mask, class_ids = dataset.load_mask(image_id) original_shape = image.shape image, window, scale, padding, crop = utils.resize_image( image, min_dim=config.IMAGE_MIN_DIM, min_scale=config.IMAGE_MIN_SCALE, max_dim=config.IMAGE_MAX_DIM, mode=config.IMAGE_RESIZE_MODE) mask = utils.resize_mask(mask, scale, padding, crop) # Random horizontal flips. # TODO: will be removed in a future update in favor of augmentation if augment: logging.warning("'augment' is deprecated. Use 'augmentation' instead.") if random.randint(0, 1): image = np.fliplr(image) mask = np.fliplr(mask) # Augmentation # This requires the imgaug lib (https://github.com/aleju/imgaug) if augmentation: import imgaug # Augmenters that are safe to apply to masks # Some, such as Affine, have settings that make them unsafe, so always # test your augmentation on masks MASK_AUGMENTERS = ["Sequential", "SomeOf", "OneOf", "Sometimes", "Fliplr", "Flipud", "CropAndPad", "Affine", "PiecewiseAffine"] def hook(images, augmenter, parents, default): """Determines which augmenters to apply to masks.""" return augmenter.__class__.__name__ in MASK_AUGMENTERS # Store shapes before augmentation to compare image_shape = image.shape mask_shape = mask.shape # Make augmenters deterministic to apply similarly to images and masks det = augmentation.to_deterministic() image = det.augment_image(image) # Change mask to np.uint8 because imgaug doesn't support np.bool mask = det.augment_image(mask.astype(np.uint8), hooks=imgaug.HooksImages(activator=hook)) # Verify that shapes didn't change assert image.shape == image_shape, "Augmentation shouldn't change image size" assert mask.shape == mask_shape, "Augmentation shouldn't change mask size" # Change mask back to bool mask = mask.astype(np.bool) # Note that some boxes might be all zeros if the corresponding mask got cropped out. # and here is to filter them out _idx = np.sum(mask, axis=(0, 1)) > 0 mask = mask[:, :, _idx] class_ids = class_ids[_idx] # Bounding boxes. Note that some boxes might be all zeros # if the corresponding mask got cropped out. # bbox: [num_instances, (y1, x1, y2, x2)] bbox = utils.extract_bboxes(mask) # Active classes # Different datasets have different classes, so track the # classes supported in the dataset of this image. active_class_ids = np.zeros([dataset.num_classes], dtype=np.int32) source_class_ids = dataset.source_class_ids[dataset.image_info[image_id]["source"]] active_class_ids[source_class_ids] = 1 # Resize masks to smaller size to reduce memory usage if use_mini_mask: mask = utils.minimize_mask(bbox, mask, config.MINI_MASK_SHAPE) # Image meta data image_meta = compose_image_meta(image_id, original_shape, image.shape, window, scale, active_class_ids) return image, image_meta, class_ids, bbox, mask def build_detection_targets(rpn_rois, gt_class_ids, gt_boxes, gt_masks, config): """Generate targets for training Stage 2 classifier and mask heads. This is not used in normal training. It's useful for debugging or to train the Mask RCNN heads without using the RPN head. Inputs: rpn_rois: [N, (y1, x1, y2, x2)] proposal boxes. gt_class_ids: [instance count] Integer class IDs gt_boxes: [instance count, (y1, x1, y2, x2)] gt_masks: [height, width, instance count] Ground truth masks. Can be full size or mini-masks. Returns: rois: [TRAIN_ROIS_PER_IMAGE, (y1, x1, y2, x2)] class_ids: [TRAIN_ROIS_PER_IMAGE]. Integer class IDs. bboxes: [TRAIN_ROIS_PER_IMAGE, NUM_CLASSES, (y, x, log(h), log(w))]. Class-specific bbox refinements. masks: [TRAIN_ROIS_PER_IMAGE, height, width, NUM_CLASSES). Class specific masks cropped to bbox boundaries and resized to neural network output size. """ assert rpn_rois.shape[0] > 0 assert gt_class_ids.dtype == np.int32, "Expected int but got {}".format( gt_class_ids.dtype) assert gt_boxes.dtype == np.int32, "Expected int but got {}".format( gt_boxes.dtype) assert gt_masks.dtype == np.bool_, "Expected bool but got {}".format( gt_masks.dtype) # It's common to add GT Boxes to ROIs but we don't do that here because # according to XinLei Chen's paper, it doesn't help. # Trim empty padding in gt_boxes and gt_masks parts instance_ids = np.where(gt_class_ids > 0)[0] assert instance_ids.shape[0] > 0, "Image must contain instances." gt_class_ids = gt_class_ids[instance_ids] gt_boxes = gt_boxes[instance_ids] gt_masks = gt_masks[:, :, instance_ids] # Compute areas of ROIs and ground truth boxes. rpn_roi_area = (rpn_rois[:, 2] - rpn_rois[:, 0]) * \ (rpn_rois[:, 3] - rpn_rois[:, 1]) gt_box_area = (gt_boxes[:, 2] - gt_boxes[:, 0]) * \ (gt_boxes[:, 3] - gt_boxes[:, 1]) # Compute overlaps [rpn_rois, gt_boxes] overlaps = np.zeros((rpn_rois.shape[0], gt_boxes.shape[0])) for i in range(overlaps.shape[1]): gt = gt_boxes[i] overlaps[:, i] = utils.compute_iou( gt, rpn_rois, gt_box_area[i], rpn_roi_area) # Assign ROIs to GT boxes rpn_roi_iou_argmax = np.argmax(overlaps, axis=1) rpn_roi_iou_max = overlaps[np.arange( overlaps.shape[0]), rpn_roi_iou_argmax] # GT box assigned to each ROI rpn_roi_gt_boxes = gt_boxes[rpn_roi_iou_argmax] rpn_roi_gt_class_ids = gt_class_ids[rpn_roi_iou_argmax] # Positive ROIs are those with >= 0.5 IoU with a GT box. fg_ids = np.where(rpn_roi_iou_max > 0.5)[0] # Negative ROIs are those with max IoU 0.1-0.5 (hard example mining) # TODO: To hard example mine or not to hard example mine, that's the question # bg_ids = np.where((rpn_roi_iou_max >= 0.1) & (rpn_roi_iou_max < 0.5))[0] bg_ids = np.where(rpn_roi_iou_max < 0.5)[0] # Subsample ROIs. Aim for 33% foreground. # FG fg_roi_count = int(config.TRAIN_ROIS_PER_IMAGE * config.ROI_POSITIVE_RATIO) if fg_ids.shape[0] > fg_roi_count: keep_fg_ids = np.random.choice(fg_ids, fg_roi_count, replace=False) else: keep_fg_ids = fg_ids # BG remaining = config.TRAIN_ROIS_PER_IMAGE - keep_fg_ids.shape[0] if bg_ids.shape[0] > remaining: keep_bg_ids = np.random.choice(bg_ids, remaining, replace=False) else: keep_bg_ids = bg_ids # Combine indices of ROIs to keep keep = np.concatenate([keep_fg_ids, keep_bg_ids]) # Need more? remaining = config.TRAIN_ROIS_PER_IMAGE - keep.shape[0] if remaining > 0: # Looks like we don't have enough samples to maintain the desired # balance. Reduce requirements and fill in the rest. This is # likely different from the Mask RCNN paper. # There is a small chance we have neither fg nor bg samples. if keep.shape[0] == 0: # Pick bg regions with easier IoU threshold bg_ids = np.where(rpn_roi_iou_max < 0.5)[0] assert bg_ids.shape[0] >= remaining keep_bg_ids = np.random.choice(bg_ids, remaining, replace=False) assert keep_bg_ids.shape[0] == remaining keep = np.concatenate([keep, keep_bg_ids]) else: # Fill the rest with repeated bg rois. keep_extra_ids = np.random.choice( keep_bg_ids, remaining, replace=True) keep = np.concatenate([keep, keep_extra_ids]) assert keep.shape[0] == config.TRAIN_ROIS_PER_IMAGE, \ "keep doesn't match ROI batch size {}, {}".format( keep.shape[0], config.TRAIN_ROIS_PER_IMAGE) # Reset the gt boxes assigned to BG ROIs. rpn_roi_gt_boxes[keep_bg_ids, :] = 0 rpn_roi_gt_class_ids[keep_bg_ids] = 0 # For each kept ROI, assign a class_id, and for FG ROIs also add bbox refinement. rois = rpn_rois[keep] roi_gt_boxes = rpn_roi_gt_boxes[keep] roi_gt_class_ids = rpn_roi_gt_class_ids[keep] roi_gt_assignment = rpn_roi_iou_argmax[keep] # Class-aware bbox deltas. [y, x, log(h), log(w)] bboxes = np.zeros((config.TRAIN_ROIS_PER_IMAGE, config.NUM_CLASSES, 4), dtype=np.float32) pos_ids = np.where(roi_gt_class_ids > 0)[0] bboxes[pos_ids, roi_gt_class_ids[pos_ids]] = utils.box_refinement( rois[pos_ids], roi_gt_boxes[pos_ids, :4]) # Normalize bbox refinements bboxes /= config.BBOX_STD_DEV # Generate class-specific target masks masks = np.zeros((config.TRAIN_ROIS_PER_IMAGE, config.MASK_SHAPE[0], config.MASK_SHAPE[1], config.NUM_CLASSES), dtype=np.float32) for i in pos_ids: class_id = roi_gt_class_ids[i] assert class_id > 0, "class id must be greater than 0" gt_id = roi_gt_assignment[i] class_mask = gt_masks[:, :, gt_id] if config.USE_MINI_MASK: # Create a mask placeholder, the size of the image placeholder = np.zeros(config.IMAGE_SHAPE[:2], dtype=bool) # GT box gt_y1, gt_x1, gt_y2, gt_x2 = gt_boxes[gt_id] gt_w = gt_x2 - gt_x1 gt_h = gt_y2 - gt_y1 # Resize mini mask to size of GT box placeholder[gt_y1:gt_y2, gt_x1:gt_x2] = \ np.round(utils.resize(class_mask, (gt_h, gt_w))).astype(bool) # Place the mini batch in the placeholder class_mask = placeholder # Pick part of the mask and resize it y1, x1, y2, x2 = rois[i].astype(np.int32) m = class_mask[y1:y2, x1:x2] mask = utils.resize(m, config.MASK_SHAPE) masks[i, :, :, class_id] = mask return rois, roi_gt_class_ids, bboxes, masks def build_rpn_targets(image_shape, anchors, gt_class_ids, gt_boxes, config): """Given the anchors and GT boxes, compute overlaps and identify positive anchors and deltas to refine them to match their corresponding GT boxes. anchors: [num_anchors, (y1, x1, y2, x2)] gt_class_ids: [num_gt_boxes] Integer class IDs. gt_boxes: [num_gt_boxes, (y1, x1, y2, x2)] Returns: rpn_match: [N] (int32) matches between anchors and GT boxes. 1 = positive anchor, -1 = negative anchor, 0 = neutral rpn_bbox: [N, (dy, dx, log(dh), log(dw))] Anchor bbox deltas. """ # RPN Match: 1 = positive anchor, -1 = negative anchor, 0 = neutral rpn_match = np.zeros([anchors.shape[0]], dtype=np.int32) # RPN bounding boxes: [max anchors per image, (dy, dx, log(dh), log(dw))] rpn_bbox = np.zeros((config.RPN_TRAIN_ANCHORS_PER_IMAGE, 4)) # Handle COCO crowds # A crowd box in COCO is a bounding box around several instances. Exclude # them from training. A crowd box is given a negative class ID. crowd_ix = np.where(gt_class_ids < 0)[0] if crowd_ix.shape[0] > 0: # Filter out crowds from ground truth class IDs and boxes non_crowd_ix = np.where(gt_class_ids > 0)[0] crowd_boxes = gt_boxes[crowd_ix] gt_class_ids = gt_class_ids[non_crowd_ix] gt_boxes = gt_boxes[non_crowd_ix] # Compute overlaps with crowd boxes [anchors, crowds] crowd_overlaps = utils.compute_overlaps(anchors, crowd_boxes) crowd_iou_max = np.amax(crowd_overlaps, axis=1) no_crowd_bool = (crowd_iou_max < 0.001) else: # All anchors don't intersect a crowd no_crowd_bool = np.ones([anchors.shape[0]], dtype=bool) # Compute overlaps [num_anchors, num_gt_boxes] overlaps = utils.compute_overlaps(anchors, gt_boxes) # Match anchors to GT Boxes # If an anchor overlaps a GT box with IoU >= 0.7 then it's positive. # If an anchor overlaps a GT box with IoU < 0.3 then it's negative. # Neutral anchors are those that don't match the conditions above, # and they don't influence the loss function. # However, don't keep any GT box unmatched (rare, but happens). Instead, # match it to the closest anchor (even if its max IoU is < 0.3). # # 1. Set negative anchors first. They get overwritten below if a GT box is # matched to them. Skip boxes in crowd areas. anchor_iou_argmax = np.argmax(overlaps, axis=1) anchor_iou_max = overlaps[np.arange(overlaps.shape[0]), anchor_iou_argmax] rpn_match[(anchor_iou_max < 0.3) & (no_crowd_bool)] = -1 # 2. Set an anchor for each GT box (regardless of IoU value). # TODO: If multiple anchors have the same IoU match all of them gt_iou_argmax = np.argmax(overlaps, axis=0) rpn_match[gt_iou_argmax] = 1 # 3. Set anchors with high overlap as positive. rpn_match[anchor_iou_max >= 0.7] = 1 # Subsample to balance positive and negative anchors # Don't let positives be more than half the anchors ids = np.where(rpn_match == 1)[0] extra = len(ids) - (config.RPN_TRAIN_ANCHORS_PER_IMAGE // 2) if extra > 0: # Reset the extra ones to neutral ids = np.random.choice(ids, extra, replace=False) rpn_match[ids] = 0 # Same for negative proposals ids = np.where(rpn_match == -1)[0] extra = len(ids) - (config.RPN_TRAIN_ANCHORS_PER_IMAGE - np.sum(rpn_match == 1)) if extra > 0: # Rest the extra ones to neutral ids = np.random.choice(ids, extra, replace=False) rpn_match[ids] = 0 # For positive anchors, compute shift and scale needed to transform them # to match the corresponding GT boxes. ids = np.where(rpn_match == 1)[0] ix = 0 # index into rpn_bbox # TODO: use box_refinement() rather than duplicating the code here for i, a in zip(ids, anchors[ids]): # Closest gt box (it might have IoU < 0.7) gt = gt_boxes[anchor_iou_argmax[i]] # Convert coordinates to center plus width/height. # GT Box gt_h = gt[2] - gt[0] gt_w = gt[3] - gt[1] gt_center_y = gt[0] + 0.5 * gt_h gt_center_x = gt[1] + 0.5 * gt_w # Anchor a_h = a[2] - a[0] a_w = a[3] - a[1] a_center_y = a[0] + 0.5 * a_h a_center_x = a[1] + 0.5 * a_w # Compute the bbox refinement that the RPN should predict. rpn_bbox[ix] = [ (gt_center_y - a_center_y) / a_h, (gt_center_x - a_center_x) / a_w, np.log(gt_h / a_h), np.log(gt_w / a_w), ] # Normalize rpn_bbox[ix] /= config.RPN_BBOX_STD_DEV ix += 1 return rpn_match, rpn_bbox def generate_random_rois(image_shape, count, gt_class_ids, gt_boxes): """Generates ROI proposals similar to what a region proposal network would generate. image_shape: [Height, Width, Depth] count: Number of ROIs to generate gt_class_ids: [N] Integer ground truth class IDs gt_boxes: [N, (y1, x1, y2, x2)] Ground truth boxes in pixels. Returns: [count, (y1, x1, y2, x2)] ROI boxes in pixels. """ # placeholder rois = np.zeros((count, 4), dtype=np.int32) # Generate random ROIs around GT boxes (90% of count) rois_per_box = int(0.9 * count / gt_boxes.shape[0]) for i in range(gt_boxes.shape[0]): gt_y1, gt_x1, gt_y2, gt_x2 = gt_boxes[i] h = gt_y2 - gt_y1 w = gt_x2 - gt_x1 # random boundaries r_y1 = max(gt_y1 - h, 0) r_y2 = min(gt_y2 + h, image_shape[0]) r_x1 = max(gt_x1 - w, 0) r_x2 = min(gt_x2 + w, image_shape[1]) # To avoid generating boxes with zero area, we generate double what # we need and filter out the extra. If we get fewer valid boxes # than we need, we loop and try again. while True: y1y2 = np.random.randint(r_y1, r_y2, (rois_per_box * 2, 2)) x1x2 = np.random.randint(r_x1, r_x2, (rois_per_box * 2, 2)) # Filter out zero area boxes threshold = 1 y1y2 = y1y2[np.abs(y1y2[:, 0] - y1y2[:, 1]) >= threshold][:rois_per_box] x1x2 = x1x2[np.abs(x1x2[:, 0] - x1x2[:, 1]) >= threshold][:rois_per_box] if y1y2.shape[0] == rois_per_box and x1x2.shape[0] == rois_per_box: break # Sort on axis 1 to ensure x1 <= x2 and y1 <= y2 and then reshape # into x1, y1, x2, y2 order x1, x2 = np.split(np.sort(x1x2, axis=1), 2, axis=1) y1, y2 = np.split(np.sort(y1y2, axis=1), 2, axis=1) box_rois = np.hstack([y1, x1, y2, x2]) rois[rois_per_box * i:rois_per_box * (i + 1)] = box_rois # Generate random ROIs anywhere in the image (10% of count) remaining_count = count - (rois_per_box * gt_boxes.shape[0]) # To avoid generating boxes with zero area, we generate double what # we need and filter out the extra. If we get fewer valid boxes # than we need, we loop and try again. while True: y1y2 = np.random.randint(0, image_shape[0], (remaining_count * 2, 2)) x1x2 = np.random.randint(0, image_shape[1], (remaining_count * 2, 2)) # Filter out zero area boxes threshold = 1 y1y2 = y1y2[np.abs(y1y2[:, 0] - y1y2[:, 1]) >= threshold][:remaining_count] x1x2 = x1x2[np.abs(x1x2[:, 0] - x1x2[:, 1]) >= threshold][:remaining_count] if y1y2.shape[0] == remaining_count and x1x2.shape[0] == remaining_count: break # Sort on axis 1 to ensure x1 <= x2 and y1 <= y2 and then reshape # into x1, y1, x2, y2 order x1, x2 = np.split(np.sort(x1x2, axis=1), 2, axis=1) y1, y2 = np.split(np.sort(y1y2, axis=1), 2, axis=1) global_rois = np.hstack([y1, x1, y2, x2]) rois[-remaining_count:] = global_rois return rois def data_generator(dataset, config, shuffle=True, augment=False, augmentation=None, random_rois=0, batch_size=1, detection_targets=False, no_augmentation_sources=None): """A generator that returns images and corresponding target class ids, bounding box deltas, and masks. dataset: The Dataset object to pick data from config: The model config object shuffle: If True, shuffles the samples before every epoch augment: (deprecated. Use augmentation instead). If true, apply random image augmentation. Currently, only horizontal flipping is offered. augmentation: Optional. An imgaug (https://github.com/aleju/imgaug) augmentation. For example, passing imgaug.augmenters.Fliplr(0.5) flips images right/left 50% of the time. random_rois: If > 0 then generate proposals to be used to train the network classifier and mask heads. Useful if training the Mask RCNN part without the RPN. batch_size: How many images to return in each call detection_targets: If True, generate detection targets (class IDs, bbox deltas, and masks). Typically for debugging or visualizations because in trainig detection targets are generated by DetectionTargetLayer. no_augmentation_sources: Optional. List of sources to exclude for augmentation. A source is string that identifies a dataset and is defined in the Dataset class. Returns a Python generator. Upon calling next() on it, the generator returns two lists, inputs and outputs. The contents of the lists differs depending on the received arguments: inputs list: - images: [batch, H, W, C] - image_meta: [batch, (meta data)] Image details. See compose_image_meta() - rpn_match: [batch, N] Integer (1=positive anchor, -1=negative, 0=neutral) - rpn_bbox: [batch, N, (dy, dx, log(dh), log(dw))] Anchor bbox deltas. - gt_class_ids: [batch, MAX_GT_INSTANCES] Integer class IDs - gt_boxes: [batch, MAX_GT_INSTANCES, (y1, x1, y2, x2)] - gt_masks: [batch, height, width, MAX_GT_INSTANCES]. The height and width are those of the image unless use_mini_mask is True, in which case they are defined in MINI_MASK_SHAPE. outputs list: Usually empty in regular training. But if detection_targets is True then the outputs list contains target class_ids, bbox deltas, and masks. """ b = 0 # batch item index image_index = -1 image_ids = np.copy(dataset.image_ids) error_count = 0 no_augmentation_sources = no_augmentation_sources or [] # Anchors # [anchor_count, (y1, x1, y2, x2)] backbone_shapes = compute_backbone_shapes(config, config.IMAGE_SHAPE) anchors = utils.generate_pyramid_anchors(config.RPN_ANCHOR_SCALES, config.RPN_ANCHOR_RATIOS, backbone_shapes, config.BACKBONE_STRIDES, config.RPN_ANCHOR_STRIDE) # Keras requires a generator to run indefinitely. while True: try: # Increment index to pick next image. Shuffle if at the start of an epoch. image_index = (image_index + 1) % len(image_ids) if shuffle and image_index == 0: np.random.shuffle(image_ids) # Get GT bounding boxes and masks for image. image_id = image_ids[image_index] # If the image source is not to be augmented pass None as augmentation if dataset.image_info[image_id]['source'] in no_augmentation_sources: image, image_meta, gt_class_ids, gt_boxes, gt_masks = \ load_image_gt(dataset, config, image_id, augment=augment, augmentation=None, use_mini_mask=config.USE_MINI_MASK) else: image, image_meta, gt_class_ids, gt_boxes, gt_masks = \ load_image_gt(dataset, config, image_id, augment=augment, augmentation=augmentation, use_mini_mask=config.USE_MINI_MASK) # Skip images that have no instances. This can happen in cases # where we train on a subset of classes and the image doesn't # have any of the classes we care about. if not np.any(gt_class_ids > 0): continue # RPN Targets rpn_match, rpn_bbox = build_rpn_targets(image.shape, anchors, gt_class_ids, gt_boxes, config) # Mask R-CNN Targets if random_rois: rpn_rois = generate_random_rois( image.shape, random_rois, gt_class_ids, gt_boxes) if detection_targets: rois, mrcnn_class_ids, mrcnn_bbox, mrcnn_mask =\ build_detection_targets( rpn_rois, gt_class_ids, gt_boxes, gt_masks, config) # Init batch arrays if b == 0: batch_image_meta = np.zeros( (batch_size,) + image_meta.shape, dtype=image_meta.dtype) batch_rpn_match = np.zeros( [batch_size, anchors.shape[0], 1], dtype=rpn_match.dtype) batch_rpn_bbox = np.zeros( [batch_size, config.RPN_TRAIN_ANCHORS_PER_IMAGE, 4], dtype=rpn_bbox.dtype) batch_images = np.zeros( (batch_size,) + image.shape, dtype=np.float32) batch_gt_class_ids = np.zeros( (batch_size, config.MAX_GT_INSTANCES), dtype=np.int32) batch_gt_boxes = np.zeros( (batch_size, config.MAX_GT_INSTANCES, 4), dtype=np.int32) batch_gt_masks = np.zeros( (batch_size, gt_masks.shape[0], gt_masks.shape[1], config.MAX_GT_INSTANCES), dtype=gt_masks.dtype) if random_rois: batch_rpn_rois = np.zeros( (batch_size, rpn_rois.shape[0], 4), dtype=rpn_rois.dtype) if detection_targets: batch_rois = np.zeros( (batch_size,) + rois.shape, dtype=rois.dtype) batch_mrcnn_class_ids = np.zeros( (batch_size,) + mrcnn_class_ids.shape, dtype=mrcnn_class_ids.dtype) batch_mrcnn_bbox = np.zeros( (batch_size,) + mrcnn_bbox.shape, dtype=mrcnn_bbox.dtype) batch_mrcnn_mask = np.zeros( (batch_size,) + mrcnn_mask.shape, dtype=mrcnn_mask.dtype) # If more instances than fits in the array, sub-sample from them. if gt_boxes.shape[0] > config.MAX_GT_INSTANCES: ids = np.random.choice( np.arange(gt_boxes.shape[0]), config.MAX_GT_INSTANCES, replace=False) gt_class_ids = gt_class_ids[ids] gt_boxes = gt_boxes[ids] gt_masks = gt_masks[:, :, ids] # Add to batch batch_image_meta[b] = image_meta batch_rpn_match[b] = rpn_match[:, np.newaxis] batch_rpn_bbox[b] = rpn_bbox batch_images[b] = mold_image(image.astype(np.float32), config) batch_gt_class_ids[b, :gt_class_ids.shape[0]] = gt_class_ids batch_gt_boxes[b, :gt_boxes.shape[0]] = gt_boxes batch_gt_masks[b, :, :, :gt_masks.shape[-1]] = gt_masks if random_rois: batch_rpn_rois[b] = rpn_rois if detection_targets: batch_rois[b] = rois batch_mrcnn_class_ids[b] = mrcnn_class_ids batch_mrcnn_bbox[b] = mrcnn_bbox batch_mrcnn_mask[b] = mrcnn_mask b += 1 # Batch full? if b >= batch_size: inputs = [batch_images, batch_image_meta, batch_rpn_match, batch_rpn_bbox, batch_gt_class_ids, batch_gt_boxes, batch_gt_masks] outputs = [] if random_rois: inputs.extend([batch_rpn_rois]) if detection_targets: inputs.extend([batch_rois]) # Keras requires that output and targets have the same number of dimensions batch_mrcnn_class_ids = np.expand_dims( batch_mrcnn_class_ids, -1) outputs.extend( [batch_mrcnn_class_ids, batch_mrcnn_bbox, batch_mrcnn_mask]) yield inputs, outputs # start a new batch b = 0 except (GeneratorExit, KeyboardInterrupt): raise except: # Log it and skip the image logging.exception("Error processing image {}".format( dataset.image_info[image_id])) error_count += 1 if error_count > 5: raise ############################################################ # MaskRCNN Class ############################################################ class MaskRCNN(): """Encapsulates the Mask RCNN model functionality. The actual Keras model is in the keras_model property. """ def __init__(self, mode, config, model_dir): """ mode: Either "training" or "inference" config: A Sub-class of the Config class model_dir: Directory to save training logs and trained weights """ assert mode in ['training', 'inference'] self.mode = mode self.config = config self.model_dir = model_dir self.set_log_dir() self.keras_model = self.build(mode=mode, config=config) def build(self, mode, config): """Build Mask R-CNN architecture. input_shape: The shape of the input image. mode: Either "training" or "inference". The inputs and outputs of the model differ accordingly. """ assert mode in ['training', 'inference'] # Image size must be dividable by 2 multiple times h, w = config.IMAGE_SHAPE[:2] if h / 2**6 != int(h / 2**6) or w / 2**6 != int(w / 2**6): raise Exception("Image size must be dividable by 2 at least 6 times " "to avoid fractions when downscaling and upscaling." "For example, use 256, 320, 384, 448, 512, ... etc. ") # Inputs input_image = KL.Input( shape=[None, None, config.IMAGE_SHAPE[2]], name="input_image") input_image_meta = KL.Input(shape=[config.IMAGE_META_SIZE], name="input_image_meta") if mode == "training": # RPN GT input_rpn_match = KL.Input( shape=[None, 1], name="input_rpn_match", dtype=tf.int32) input_rpn_bbox = KL.Input( shape=[None, 4], name="input_rpn_bbox", dtype=tf.float32) # Detection GT (class IDs, bounding boxes, and masks) # 1. GT Class IDs (zero padded) input_gt_class_ids = KL.Input( shape=[None], name="input_gt_class_ids", dtype=tf.int32) # 2. GT Boxes in pixels (zero padded) # [batch, MAX_GT_INSTANCES, (y1, x1, y2, x2)] in image coordinates input_gt_boxes = KL.Input( shape=[None, 4], name="input_gt_boxes", dtype=tf.float32) # Normalize coordinates gt_boxes = KL.Lambda(lambda x: norm_boxes_graph( x, K.shape(input_image)[1:3]))(input_gt_boxes) # 3. GT Masks (zero padded) # [batch, height, width, MAX_GT_INSTANCES] if config.USE_MINI_MASK: input_gt_masks = KL.Input( shape=[config.MINI_MASK_SHAPE[0], config.MINI_MASK_SHAPE[1], None], name="input_gt_masks", dtype=bool) else: input_gt_masks = KL.Input( shape=[config.IMAGE_SHAPE[0], config.IMAGE_SHAPE[1], None], name="input_gt_masks", dtype=bool) elif mode == "inference": # Anchors in normalized coordinates input_anchors = KL.Input(shape=[None, 4], name="input_anchors") # Build the shared convolutional layers. # Bottom-up Layers # Returns a list of the last layers of each stage, 5 in total. # Don't create the thead (stage 5), so we pick the 4th item in the list. if callable(config.BACKBONE): _, C2, C3, C4, C5 = config.BACKBONE(input_image, stage5=True, train_bn=config.TRAIN_BN) else: _, C2, C3, C4, C5 = resnet_graph(input_image, config.BACKBONE, stage5=True, train_bn=config.TRAIN_BN) # Top-down Layers # TODO: add assert to varify feature map sizes match what's in config P5 = KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (1, 1), name='fpn_c5p5')(C5) P4 = KL.Add(name="fpn_p4add")([ KL.UpSampling2D(size=(2, 2), name="fpn_p5upsampled")(P5), KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (1, 1), name='fpn_c4p4')(C4)]) P3 = KL.Add(name="fpn_p3add")([ KL.UpSampling2D(size=(2, 2), name="fpn_p4upsampled")(P4), KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (1, 1), name='fpn_c3p3')(C3)]) P2 = KL.Add(name="fpn_p2add")([ KL.UpSampling2D(size=(2, 2), name="fpn_p3upsampled")(P3), KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (1, 1), name='fpn_c2p2')(C2)]) # Attach 3x3 conv to all P layers to get the final feature maps. P2 = KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (3, 3), padding="SAME", name="fpn_p2")(P2) P3 = KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (3, 3), padding="SAME", name="fpn_p3")(P3) P4 = KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (3, 3), padding="SAME", name="fpn_p4")(P4) P5 = KL.Conv2D(config.TOP_DOWN_PYRAMID_SIZE, (3, 3), padding="SAME", name="fpn_p5")(P5) # P6 is used for the 5th anchor scale in RPN. Generated by # subsampling from P5 with stride of 2. P6 = KL.MaxPooling2D(pool_size=(1, 1), strides=2, name="fpn_p6")(P5) # Note that P6 is used in RPN, but not in the classifier heads. rpn_feature_maps = [P2, P3, P4, P5, P6] mrcnn_feature_maps = [P2, P3, P4, P5] # Anchors if mode == "training": anchors = self.get_anchors(config.IMAGE_SHAPE) # Duplicate across the batch dimension because Keras requires it # TODO: can this be optimized to avoid duplicating the anchors? anchors = np.broadcast_to(anchors, (config.BATCH_SIZE,) + anchors.shape) # A hack to get around Keras's bad support for constants anchors = KL.Lambda(lambda x: tf.Variable(anchors), name="anchors")(input_image) else: anchors = input_anchors # RPN Model rpn = build_rpn_model(config.RPN_ANCHOR_STRIDE, len(config.RPN_ANCHOR_RATIOS), config.TOP_DOWN_PYRAMID_SIZE) # Loop through pyramid layers layer_outputs = [] # list of lists for p in rpn_feature_maps: layer_outputs.append(rpn([p])) # Concatenate layer outputs # Convert from list of lists of level outputs to list of lists # of outputs across levels. # e.g. [[a1, b1, c1], [a2, b2, c2]] => [[a1, a2], [b1, b2], [c1, c2]] output_names = ["rpn_class_logits", "rpn_class", "rpn_bbox"] outputs = list(zip(*layer_outputs)) outputs = [KL.Concatenate(axis=1, name=n)(list(o)) for o, n in zip(outputs, output_names)] rpn_class_logits, rpn_class, rpn_bbox = outputs # Generate proposals # Proposals are [batch, N, (y1, x1, y2, x2)] in normalized coordinates # and zero padded. proposal_count = config.POST_NMS_ROIS_TRAINING if mode == "training"\ else config.POST_NMS_ROIS_INFERENCE rpn_rois = ProposalLayer( proposal_count=proposal_count, nms_threshold=config.RPN_NMS_THRESHOLD, name="ROI", config=config)([rpn_class, rpn_bbox, anchors]) if mode == "training": # Class ID mask to mark class IDs supported by the dataset the image # came from. active_class_ids = KL.Lambda( lambda x: parse_image_meta_graph(x)["active_class_ids"] )(input_image_meta) if not config.USE_RPN_ROIS: # Ignore predicted ROIs and use ROIs provided as an input. input_rois = KL.Input(shape=[config.POST_NMS_ROIS_TRAINING, 4], name="input_roi", dtype=np.int32) # Normalize coordinates target_rois = KL.Lambda(lambda x: norm_boxes_graph( x, K.shape(input_image)[1:3]))(input_rois) else: target_rois = rpn_rois # Generate detection targets # Subsamples proposals and generates target outputs for training # Note that proposal class IDs, gt_boxes, and gt_masks are zero # padded. Equally, returned rois and targets are zero padded. rois, target_class_ids, target_bbox, target_mask =\ DetectionTargetLayer(config, name="proposal_targets")([ target_rois, input_gt_class_ids, gt_boxes, input_gt_masks]) # Network Heads # TODO: verify that this handles zero padded ROIs mrcnn_class_logits, mrcnn_class, mrcnn_bbox =\ fpn_classifier_graph(rois, mrcnn_feature_maps, input_image_meta, config.POOL_SIZE, config.NUM_CLASSES, train_bn=config.TRAIN_BN, fc_layers_size=config.FPN_CLASSIF_FC_LAYERS_SIZE) mrcnn_mask = build_fpn_mask_graph(rois, mrcnn_feature_maps, input_image_meta, config.MASK_POOL_SIZE, config.NUM_CLASSES, train_bn=config.TRAIN_BN) # TODO: clean up (use tf.identify if necessary) output_rois = KL.Lambda(lambda x: x * 1, name="output_rois")(rois) # Losses rpn_class_loss = KL.Lambda(lambda x: rpn_class_loss_graph(*x), name="rpn_class_loss")( [input_rpn_match, rpn_class_logits]) rpn_bbox_loss = KL.Lambda(lambda x: rpn_bbox_loss_graph(config, *x), name="rpn_bbox_loss")( [input_rpn_bbox, input_rpn_match, rpn_bbox]) class_loss = KL.Lambda(lambda x: mrcnn_class_loss_graph(*x), name="mrcnn_class_loss")( [target_class_ids, mrcnn_class_logits, active_class_ids]) bbox_loss = KL.Lambda(lambda x: mrcnn_bbox_loss_graph(*x), name="mrcnn_bbox_loss")( [target_bbox, target_class_ids, mrcnn_bbox]) mask_loss = KL.Lambda(lambda x: mrcnn_mask_loss_graph(*x), name="mrcnn_mask_loss")( [target_mask, target_class_ids, mrcnn_mask]) # Model inputs = [input_image, input_image_meta, input_rpn_match, input_rpn_bbox, input_gt_class_ids, input_gt_boxes, input_gt_masks] if not config.USE_RPN_ROIS: inputs.append(input_rois) outputs = [rpn_class_logits, rpn_class, rpn_bbox, mrcnn_class_logits, mrcnn_class, mrcnn_bbox, mrcnn_mask, rpn_rois, output_rois, rpn_class_loss, rpn_bbox_loss, class_loss, bbox_loss, mask_loss] model = KM.Model(inputs, outputs, name='mask_rcnn') else: # Network Heads # Proposal classifier and BBox regressor heads mrcnn_class_logits, mrcnn_class, mrcnn_bbox =\ fpn_classifier_graph(rpn_rois, mrcnn_feature_maps, input_image_meta, config.POOL_SIZE, config.NUM_CLASSES, train_bn=config.TRAIN_BN, fc_layers_size=config.FPN_CLASSIF_FC_LAYERS_SIZE) # Detections # output is [batch, num_detections, (y1, x1, y2, x2, class_id, score)] in # normalized coordinates detections = DetectionLayer(config, name="mrcnn_detection")( [rpn_rois, mrcnn_class, mrcnn_bbox, input_image_meta]) # Create masks for detections detection_boxes = KL.Lambda(lambda x: x[..., :4])(detections) mrcnn_mask = build_fpn_mask_graph(detection_boxes, mrcnn_feature_maps, input_image_meta, config.MASK_POOL_SIZE, config.NUM_CLASSES, train_bn=config.TRAIN_BN) model = KM.Model([input_image, input_image_meta, input_anchors], [detections, mrcnn_class, mrcnn_bbox, mrcnn_mask, rpn_rois, rpn_class, rpn_bbox], name='mask_rcnn') # Add multi-GPU support. if config.GPU_COUNT > 1: from mrcnn.parallel_model import ParallelModel model = ParallelModel(model, config.GPU_COUNT) return model def find_last(self): """Finds the last checkpoint file of the last trained model in the model directory. Returns: The path of the last checkpoint file """ # Get directory names. Each directory corresponds to a model dir_names = next(os.walk(self.model_dir))[1] key = self.config.NAME.lower() dir_names = filter(lambda f: f.startswith(key), dir_names) dir_names = sorted(dir_names) if not dir_names: import errno raise FileNotFoundError( errno.ENOENT, "Could not find model directory under {}".format(self.model_dir)) # Pick last directory dir_name = os.path.join(self.model_dir, dir_names[-1]) # Find the last checkpoint checkpoints = next(os.walk(dir_name))[2] checkpoints = filter(lambda f: f.startswith("mask_rcnn"), checkpoints) checkpoints = sorted(checkpoints) if not checkpoints: import errno raise FileNotFoundError( errno.ENOENT, "Could not find weight files in {}".format(dir_name)) checkpoint = os.path.join(dir_name, checkpoints[-1]) return checkpoint def load_weights(self, filepath, by_name=False, exclude=None): """Modified version of the corresponding Keras function with the addition of multi-GPU support and the ability to exclude some layers from loading. exclude: list of layer names to exclude """ import h5py # Conditional import to support versions of Keras before 2.2 # TODO: remove in about 6 months (end of 2018) try: from keras.engine import saving except ImportError: # Keras before 2.2 used the 'topology' namespace. from keras.engine import topology as saving if exclude: by_name = True if h5py is None: raise ImportError('`load_weights` requires h5py.') f = h5py.File(filepath, mode='r') if 'layer_names' not in f.attrs and 'model_weights' in f: f = f['model_weights'] # In multi-GPU training, we wrap the model. Get layers # of the inner model because they have the weights. keras_model = self.keras_model layers = keras_model.inner_model.layers if hasattr(keras_model, "inner_model")\ else keras_model.layers # Exclude some layers if exclude: layers = filter(lambda l: l.name not in exclude, layers) if by_name: saving.load_weights_from_hdf5_group_by_name(f, layers) else: saving.load_weights_from_hdf5_group(f, layers) if hasattr(f, 'close'): f.close() # Update the log directory self.set_log_dir(filepath) def get_imagenet_weights(self): """Downloads ImageNet trained weights from Keras. Returns path to weights file. """ from keras.utils.data_utils import get_file TF_WEIGHTS_PATH_NO_TOP = 'https://github.com/fchollet/deep-learning-models/'\ 'releases/download/v0.2/'\ 'resnet50_weights_tf_dim_ordering_tf_kernels_notop.h5' weights_path = get_file('resnet50_weights_tf_dim_ordering_tf_kernels_notop.h5', TF_WEIGHTS_PATH_NO_TOP, cache_subdir='models', md5_hash='a268eb855778b3df3c7506639542a6af') return weights_path def compile(self, learning_rate, momentum): """Gets the model ready for training. Adds losses, regularization, and metrics. Then calls the Keras compile() function. """ # Optimizer object optimizer = keras.optimizers.SGD( lr=learning_rate, momentum=momentum, clipnorm=self.config.GRADIENT_CLIP_NORM) # Add Losses # First, clear previously set losses to avoid duplication self.keras_model._losses = [] self.keras_model._per_input_losses = {} loss_names = [ "rpn_class_loss", "rpn_bbox_loss", "mrcnn_class_loss", "mrcnn_bbox_loss", "mrcnn_mask_loss"] for name in loss_names: layer = self.keras_model.get_layer(name) if layer.output in self.keras_model.losses: continue loss = ( tf.reduce_mean(layer.output, keepdims=True) * self.config.LOSS_WEIGHTS.get(name, 1.)) self.keras_model.add_loss(loss) # Add L2 Regularization # Skip gamma and beta weights of batch normalization layers. reg_losses = [ keras.regularizers.l2(self.config.WEIGHT_DECAY)(w) / tf.cast(tf.size(w), tf.float32) for w in self.keras_model.trainable_weights if 'gamma' not in w.name and 'beta' not in w.name] self.keras_model.add_loss(tf.add_n(reg_losses)) # Compile self.keras_model.compile( optimizer=optimizer, loss=[None] * len(self.keras_model.outputs)) # Add metrics for losses for name in loss_names: if name in self.keras_model.metrics_names: continue layer = self.keras_model.get_layer(name) self.keras_model.metrics_names.append(name) loss = ( tf.reduce_mean(layer.output, keepdims=True) * self.config.LOSS_WEIGHTS.get(name, 1.)) self.keras_model.metrics_tensors.append(loss) def set_trainable(self, layer_regex, keras_model=None, indent=0, verbose=1): """Sets model layers as trainable if their names match the given regular expression. """ # Print message on the first call (but not on recursive calls) if verbose > 0 and keras_model is None: log("Selecting layers to train") keras_model = keras_model or self.keras_model # In multi-GPU training, we wrap the model. Get layers # of the inner model because they have the weights. layers = keras_model.inner_model.layers if hasattr(keras_model, "inner_model")\ else keras_model.layers for layer in layers: # Is the layer a model? if layer.__class__.__name__ == 'Model': print("In model: ", layer.name) self.set_trainable( layer_regex, keras_model=layer, indent=indent + 4) continue if not layer.weights: continue # Is it trainable? trainable = bool(re.fullmatch(layer_regex, layer.name)) # Update layer. If layer is a container, update inner layer. if layer.__class__.__name__ == 'TimeDistributed': layer.layer.trainable = trainable else: layer.trainable = trainable # Print trainable layer names if trainable and verbose > 0: log("{}{:20} ({})".format(" " * indent, layer.name, layer.__class__.__name__)) def set_log_dir(self, model_path=None): """Sets the model log directory and epoch counter. model_path: If None, or a format different from what this code uses then set a new log directory and start epochs from 0. Otherwise, extract the log directory and the epoch counter from the file name. """ # Set date and epoch counter as if starting a new model self.epoch = 0 now = datetime.datetime.now() # If we have a model path with date and epochs use them if model_path: # Continue from we left of. Get epoch and date from the file name # A sample model path might look like: # \path\to\logs\coco20171029T2315\mask_rcnn_coco_0001.h5 (Windows) # /path/to/logs/coco20171029T2315/mask_rcnn_coco_0001.h5 (Linux) regex = r".*[/\\][\w-]+(\d{4})(\d{2})(\d{2})T(\d{2})(\d{2})[/\\]mask\_rcnn\_[\w-]+(\d{4})\.h5" m = re.match(regex, model_path) if m: now = datetime.datetime(int(m.group(1)), int(m.group(2)), int(m.group(3)), int(m.group(4)), int(m.group(5))) # Epoch number in file is 1-based, and in Keras code it's 0-based. # So, adjust for that then increment by one to start from the next epoch self.epoch = int(m.group(6)) - 1 + 1 print('Re-starting from epoch %d' % self.epoch) # Directory for training logs self.log_dir = os.path.join(self.model_dir, "{}{:%Y%m%dT%H%M}".format( self.config.NAME.lower(), now)) # Path to save after each epoch. Include placeholders that get filled by Keras. self.checkpoint_path = os.path.join(self.log_dir, "mask_rcnn_{}_*epoch*.h5".format( self.config.NAME.lower())) self.checkpoint_path = self.checkpoint_path.replace( "*epoch*", "{epoch:04d}") def train(self, train_dataset, val_dataset, learning_rate, epochs, layers, augmentation=None, custom_callbacks=None, no_augmentation_sources=None): """Train the model. train_dataset, val_dataset: Training and validation Dataset objects. learning_rate: The learning rate to train with epochs: Number of training epochs. Note that previous training epochs are considered to be done alreay, so this actually determines the epochs to train in total rather than in this particaular call. layers: Allows selecting wich layers to train. It can be: - A regular expression to match layer names to train - One of these predefined values: heads: The RPN, classifier and mask heads of the network all: All the layers 3+: Train Resnet stage 3 and up 4+: Train Resnet stage 4 and up 5+: Train Resnet stage 5 and up augmentation: Optional. An imgaug (https://github.com/aleju/imgaug) augmentation. For example, passing imgaug.augmenters.Fliplr(0.5) flips images right/left 50% of the time. You can pass complex augmentations as well. This augmentation applies 50% of the time, and when it does it flips images right/left half the time and adds a Gaussian blur with a random sigma in range 0 to 5. augmentation = imgaug.augmenters.Sometimes(0.5, [ imgaug.augmenters.Fliplr(0.5), imgaug.augmenters.GaussianBlur(sigma=(0.0, 5.0)) ]) custom_callbacks: Optional. Add custom callbacks to be called with the keras fit_generator method. Must be list of type keras.callbacks. no_augmentation_sources: Optional. List of sources to exclude for augmentation. A source is string that identifies a dataset and is defined in the Dataset class. """ assert self.mode == "training", "Create model in training mode." # Pre-defined layer regular expressions layer_regex = { # all layers but the backbone "heads": r"(mrcnn\_.*)|(rpn\_.*)|(fpn\_.*)", # From a specific Resnet stage and up "3+": r"(res3.*)|(bn3.*)|(res4.*)|(bn4.*)|(res5.*)|(bn5.*)|(mrcnn\_.*)|(rpn\_.*)|(fpn\_.*)", "4+": r"(res4.*)|(bn4.*)|(res5.*)|(bn5.*)|(mrcnn\_.*)|(rpn\_.*)|(fpn\_.*)", "5+": r"(res5.*)|(bn5.*)|(mrcnn\_.*)|(rpn\_.*)|(fpn\_.*)", # All layers "all": ".*", } if layers in layer_regex.keys(): layers = layer_regex[layers] # Data generators train_generator = data_generator(train_dataset, self.config, shuffle=True, augmentation=augmentation, batch_size=self.config.BATCH_SIZE, no_augmentation_sources=no_augmentation_sources) val_generator = data_generator(val_dataset, self.config, shuffle=True, batch_size=self.config.BATCH_SIZE) # Create log_dir if it does not exist if not os.path.exists(self.log_dir): os.makedirs(self.log_dir) # Callbacks callbacks = [ keras.callbacks.TensorBoard(log_dir=self.log_dir, histogram_freq=0, write_graph=True, write_images=False), keras.callbacks.ModelCheckpoint(self.checkpoint_path, verbose=0, save_weights_only=True), ] # Add custom callbacks to the list if custom_callbacks: callbacks += custom_callbacks # Train log("\nStarting at epoch {}. LR={}\n".format(self.epoch, learning_rate)) log("Checkpoint Path: {}".format(self.checkpoint_path)) self.set_trainable(layers) self.compile(learning_rate, self.config.LEARNING_MOMENTUM) # Work-around for Windows: Keras fails on Windows when using # multiprocessing workers. See discussion here: # https://github.com/matterport/Mask_RCNN/issues/13#issuecomment-353124009 if os.name is 'nt': workers = 0 else: workers = multiprocessing.cpu_count() self.keras_model.fit_generator( train_generator, initial_epoch=self.epoch, epochs=epochs, steps_per_epoch=self.config.STEPS_PER_EPOCH, callbacks=callbacks, validation_data=val_generator, validation_steps=self.config.VALIDATION_STEPS, max_queue_size=100, workers=workers, use_multiprocessing=True, ) self.epoch = max(self.epoch, epochs) def mold_inputs(self, images): """Takes a list of images and modifies them to the format expected as an input to the neural network. images: List of image matrices [height,width,depth]. Images can have different sizes. Returns 3 Numpy matrices: molded_images: [N, h, w, 3]. Images resized and normalized. image_metas: [N, length of meta data]. Details about each image. windows: [N, (y1, x1, y2, x2)]. The portion of the image that has the original image (padding excluded). """ molded_images = [] image_metas = [] windows = [] for image in images: # Resize image # TODO: move resizing to mold_image() molded_image, window, scale, padding, crop = utils.resize_image( image, min_dim=self.config.IMAGE_MIN_DIM, min_scale=self.config.IMAGE_MIN_SCALE, max_dim=self.config.IMAGE_MAX_DIM, mode=self.config.IMAGE_RESIZE_MODE) molded_image = mold_image(molded_image, self.config) # Build image_meta image_meta = compose_image_meta( 0, image.shape, molded_image.shape, window, scale, np.zeros([self.config.NUM_CLASSES], dtype=np.int32)) # Append molded_images.append(molded_image) windows.append(window) image_metas.append(image_meta) # Pack into arrays molded_images = np.stack(molded_images) image_metas = np.stack(image_metas) windows = np.stack(windows) return molded_images, image_metas, windows def unmold_detections(self, detections, mrcnn_mask, original_image_shape, image_shape, window): """Reformats the detections of one image from the format of the neural network output to a format suitable for use in the rest of the application. detections: [N, (y1, x1, y2, x2, class_id, score)] in normalized coordinates mrcnn_mask: [N, height, width, num_classes] original_image_shape: [H, W, C] Original image shape before resizing image_shape: [H, W, C] Shape of the image after resizing and padding window: [y1, x1, y2, x2] Pixel coordinates of box in the image where the real image is excluding the padding. Returns: boxes: [N, (y1, x1, y2, x2)] Bounding boxes in pixels class_ids: [N] Integer class IDs for each bounding box scores: [N] Float probability scores of the class_id masks: [height, width, num_instances] Instance masks """ # How many detections do we have? # Detections array is padded with zeros. Find the first class_id == 0. zero_ix = np.where(detections[:, 4] == 0)[0] N = zero_ix[0] if zero_ix.shape[0] > 0 else detections.shape[0] # Extract boxes, class_ids, scores, and class-specific masks boxes = detections[:N, :4] class_ids = detections[:N, 4].astype(np.int32) scores = detections[:N, 5] masks = mrcnn_mask[np.arange(N), :, :, class_ids] # Translate normalized coordinates in the resized image to pixel # coordinates in the original image before resizing window = utils.norm_boxes(window, image_shape[:2]) wy1, wx1, wy2, wx2 = window shift = np.array([wy1, wx1, wy1, wx1]) wh = wy2 - wy1 # window height ww = wx2 - wx1 # window width scale = np.array([wh, ww, wh, ww]) # Convert boxes to normalized coordinates on the window boxes = np.divide(boxes - shift, scale) # Convert boxes to pixel coordinates on the original image boxes = utils.denorm_boxes(boxes, original_image_shape[:2]) # Filter out detections with zero area. Happens in early training when # network weights are still random exclude_ix = np.where( (boxes[:, 2] - boxes[:, 0]) * (boxes[:, 3] - boxes[:, 1]) <= 0)[0] if exclude_ix.shape[0] > 0: boxes = np.delete(boxes, exclude_ix, axis=0) class_ids = np.delete(class_ids, exclude_ix, axis=0) scores = np.delete(scores, exclude_ix, axis=0) masks = np.delete(masks, exclude_ix, axis=0) N = class_ids.shape[0] # Resize masks to original image size and set boundary threshold. full_masks = [] for i in range(N): # Convert neural network mask to full size mask full_mask = utils.unmold_mask(masks[i], boxes[i], original_image_shape) full_masks.append(full_mask) full_masks = np.stack(full_masks, axis=-1)\ if full_masks else np.empty(original_image_shape[:2] + (0,)) return boxes, class_ids, scores, full_masks def detect(self, images, verbose=0): """Runs the detection pipeline. images: List of images, potentially of different sizes. Returns a list of dicts, one dict per image. The dict contains: rois: [N, (y1, x1, y2, x2)] detection bounding boxes class_ids: [N] int class IDs scores: [N] float probability scores for the class IDs masks: [H, W, N] instance binary masks """ assert self.mode == "inference", "Create model in inference mode." assert len( images) == self.config.BATCH_SIZE, "len(images) must be equal to BATCH_SIZE" if verbose: log("Processing {} images".format(len(images))) for image in images: log("image", image) # Mold inputs to format expected by the neural network molded_images, image_metas, windows = self.mold_inputs(images) # Validate image sizes # All images in a batch MUST be of the same size image_shape = molded_images[0].shape for g in molded_images[1:]: assert g.shape == image_shape,\ "After resizing, all images must have the same size. Check IMAGE_RESIZE_MODE and image sizes." # Anchors anchors = self.get_anchors(image_shape) # Duplicate across the batch dimension because Keras requires it # TODO: can this be optimized to avoid duplicating the anchors? anchors = np.broadcast_to(anchors, (self.config.BATCH_SIZE,) + anchors.shape) if verbose: log("molded_images", molded_images) log("image_metas", image_metas) log("anchors", anchors) # Run object detection detections, _, _, mrcnn_mask, _, _, _ =\ self.keras_model.predict([molded_images, image_metas, anchors], verbose=0) # Process detections results = [] for i, image in enumerate(images): final_rois, final_class_ids, final_scores, final_masks =\ self.unmold_detections(detections[i], mrcnn_mask[i], image.shape, molded_images[i].shape, windows[i]) results.append({ "rois": final_rois, "class_ids": final_class_ids, "scores": final_scores, "masks": final_masks, }) return results def detect_molded(self, molded_images, image_metas, verbose=0): """Runs the detection pipeline, but expect inputs that are molded already. Used mostly for debugging and inspecting the model. molded_images: List of images loaded using load_image_gt() image_metas: image meta data, also returned by load_image_gt() Returns a list of dicts, one dict per image. The dict contains: rois: [N, (y1, x1, y2, x2)] detection bounding boxes class_ids: [N] int class IDs scores: [N] float probability scores for the class IDs masks: [H, W, N] instance binary masks """ assert self.mode == "inference", "Create model in inference mode." assert len(molded_images) == self.config.BATCH_SIZE,\ "Number of images must be equal to BATCH_SIZE" if verbose: log("Processing {} images".format(len(molded_images))) for image in molded_images: log("image", image) # Validate image sizes # All images in a batch MUST be of the same size image_shape = molded_images[0].shape for g in molded_images[1:]: assert g.shape == image_shape, "Images must have the same size" # Anchors anchors = self.get_anchors(image_shape) # Duplicate across the batch dimension because Keras requires it # TODO: can this be optimized to avoid duplicating the anchors? anchors = np.broadcast_to(anchors, (self.config.BATCH_SIZE,) + anchors.shape) if verbose: log("molded_images", molded_images) log("image_metas", image_metas) log("anchors", anchors) # Run object detection detections, _, _, mrcnn_mask, _, _, _ =\ self.keras_model.predict([molded_images, image_metas, anchors], verbose=0) # Process detections results = [] for i, image in enumerate(molded_images): window = [0, 0, image.shape[0], image.shape[1]] final_rois, final_class_ids, final_scores, final_masks =\ self.unmold_detections(detections[i], mrcnn_mask[i], image.shape, molded_images[i].shape, window) results.append({ "rois": final_rois, "class_ids": final_class_ids, "scores": final_scores, "masks": final_masks, }) return results def get_anchors(self, image_shape): """Returns anchor pyramid for the given image size.""" backbone_shapes = compute_backbone_shapes(self.config, image_shape) # Cache anchors and reuse if image shape is the same if not hasattr(self, "_anchor_cache"): self._anchor_cache = {} if not tuple(image_shape) in self._anchor_cache: # Generate Anchors a = utils.generate_pyramid_anchors( self.config.RPN_ANCHOR_SCALES, self.config.RPN_ANCHOR_RATIOS, backbone_shapes, self.config.BACKBONE_STRIDES, self.config.RPN_ANCHOR_STRIDE) # Keep a copy of the latest anchors in pixel coordinates because # it's used in inspect_model notebooks. # TODO: Remove this after the notebook are refactored to not use it self.anchors = a # Normalize coordinates self._anchor_cache[tuple(image_shape)] = utils.norm_boxes(a, image_shape[:2]) return self._anchor_cache[tuple(image_shape)] def ancestor(self, tensor, name, checked=None): """Finds the ancestor of a TF tensor in the computation graph. tensor: TensorFlow symbolic tensor. name: Name of ancestor tensor to find checked: For internal use. A list of tensors that were already searched to avoid loops in traversing the graph. """ checked = checked if checked is not None else [] # Put a limit on how deep we go to avoid very long loops if len(checked) > 500: return None # Convert name to a regex and allow matching a number prefix # because Keras adds them automatically if isinstance(name, str): name = re.compile(name.replace("/", r"(\_\d+)*/")) parents = tensor.op.inputs for p in parents: if p in checked: continue if bool(re.fullmatch(name, p.name)): return p checked.append(p) a = self.ancestor(p, name, checked) if a is not None: return a return None def find_trainable_layer(self, layer): """If a layer is encapsulated by another layer, this function digs through the encapsulation and returns the layer that holds the weights. """ if layer.__class__.__name__ == 'TimeDistributed': return self.find_trainable_layer(layer.layer) return layer def get_trainable_layers(self): """Returns a list of layers that have weights.""" layers = [] # Loop through all layers for l in self.keras_model.layers: # If layer is a wrapper, find inner trainable layer l = self.find_trainable_layer(l) # Include layer if it has weights if l.get_weights(): layers.append(l) return layers def run_graph(self, images, outputs, image_metas=None): """Runs a sub-set of the computation graph that computes the given outputs. image_metas: If provided, the images are assumed to be already molded (i.e. resized, padded, and normalized) outputs: List of tuples (name, tensor) to compute. The tensors are symbolic TensorFlow tensors and the names are for easy tracking. Returns an ordered dict of results. Keys are the names received in the input and values are Numpy arrays. """ model = self.keras_model # Organize desired outputs into an ordered dict outputs = OrderedDict(outputs) for o in outputs.values(): assert o is not None # Build a Keras function to run parts of the computation graph inputs = model.inputs if model.uses_learning_phase and not isinstance(K.learning_phase(), int): inputs += [K.learning_phase()] kf = K.function(model.inputs, list(outputs.values())) # Prepare inputs if image_metas is None: molded_images, image_metas, _ = self.mold_inputs(images) else: molded_images = images image_shape = molded_images[0].shape # Anchors anchors = self.get_anchors(image_shape) # Duplicate across the batch dimension because Keras requires it # TODO: can this be optimized to avoid duplicating the anchors? anchors = np.broadcast_to(anchors, (self.config.BATCH_SIZE,) + anchors.shape) model_in = [molded_images, image_metas, anchors] # Run inference if model.uses_learning_phase and not isinstance(K.learning_phase(), int): model_in.append(0.) outputs_np = kf(model_in) # Pack the generated Numpy arrays into a a dict and log the results. outputs_np = OrderedDict([(k, v) for k, v in zip(outputs.keys(), outputs_np)]) for k, v in outputs_np.items(): log(k, v) return outputs_np ############################################################ # Data Formatting ############################################################ def compose_image_meta(image_id, original_image_shape, image_shape, window, scale, active_class_ids): """Takes attributes of an image and puts them in one 1D array. image_id: An int ID of the image. Useful for debugging. original_image_shape: [H, W, C] before resizing or padding. image_shape: [H, W, C] after resizing and padding window: (y1, x1, y2, x2) in pixels. The area of the image where the real image is (excluding the padding) scale: The scaling factor applied to the original image (float32) active_class_ids: List of class_ids available in the dataset from which the image came. Useful if training on images from multiple datasets where not all classes are present in all datasets. """ meta = np.array( [image_id] + # size=1 list(original_image_shape) + # size=3 list(image_shape) + # size=3 list(window) + # size=4 (y1, x1, y2, x2) in image cooredinates [scale] + # size=1 list(active_class_ids) # size=num_classes ) return meta def parse_image_meta(meta): """Parses an array that contains image attributes to its components. See compose_image_meta() for more details. meta: [batch, meta length] where meta length depends on NUM_CLASSES Returns a dict of the parsed values. """ image_id = meta[:, 0] original_image_shape = meta[:, 1:4] image_shape = meta[:, 4:7] window = meta[:, 7:11] # (y1, x1, y2, x2) window of image in in pixels scale = meta[:, 11] active_class_ids = meta[:, 12:] return { "image_id": image_id.astype(np.int32), "original_image_shape": original_image_shape.astype(np.int32), "image_shape": image_shape.astype(np.int32), "window": window.astype(np.int32), "scale": scale.astype(np.float32), "active_class_ids": active_class_ids.astype(np.int32), } def parse_image_meta_graph(meta): """Parses a tensor that contains image attributes to its components. See compose_image_meta() for more details. meta: [batch, meta length] where meta length depends on NUM_CLASSES Returns a dict of the parsed tensors. """ image_id = meta[:, 0] original_image_shape = meta[:, 1:4] image_shape = meta[:, 4:7] window = meta[:, 7:11] # (y1, x1, y2, x2) window of image in in pixels scale = meta[:, 11] active_class_ids = meta[:, 12:] return { "image_id": image_id, "original_image_shape": original_image_shape, "image_shape": image_shape, "window": window, "scale": scale, "active_class_ids": active_class_ids, } def mold_image(images, config): """Expects an RGB image (or array of images) and subtracts the mean pixel and converts it to float. Expects image colors in RGB order. """ return images.astype(np.float32) - config.MEAN_PIXEL def unmold_image(normalized_images, config): """Takes a image normalized with mold() and returns the original.""" return (normalized_images + config.MEAN_PIXEL).astype(np.uint8) ############################################################ # Miscellenous Graph Functions ############################################################ def trim_zeros_graph(boxes, name=None): """Often boxes are represented with matrices of shape [N, 4] and are padded with zeros. This removes zero boxes. boxes: [N, 4] matrix of boxes. non_zeros: [N] a 1D boolean mask identifying the rows to keep """ non_zeros = tf.cast(tf.reduce_sum(tf.abs(boxes), axis=1), tf.bool) boxes = tf.boolean_mask(boxes, non_zeros, name=name) return boxes, non_zeros def batch_pack_graph(x, counts, num_rows): """Picks different number of values from each row in x depending on the values in counts. """ outputs = [] for i in range(num_rows): outputs.append(x[i, :counts[i]]) return tf.concat(outputs, axis=0) def norm_boxes_graph(boxes, shape): """Converts boxes from pixel coordinates to normalized coordinates. boxes: [..., (y1, x1, y2, x2)] in pixel coordinates shape: [..., (height, width)] in pixels Note: In pixel coordinates (y2, x2) is outside the box. But in normalized coordinates it's inside the box. Returns: [..., (y1, x1, y2, x2)] in normalized coordinates """ h, w = tf.split(tf.cast(shape, tf.float32), 2) scale = tf.concat([h, w, h, w], axis=-1) - tf.constant(1.0) shift = tf.constant([0., 0., 1., 1.]) return tf.divide(boxes - shift, scale) def denorm_boxes_graph(boxes, shape): """Converts boxes from normalized coordinates to pixel coordinates. boxes: [..., (y1, x1, y2, x2)] in normalized coordinates shape: [..., (height, width)] in pixels Note: In pixel coordinates (y2, x2) is outside the box. But in normalized coordinates it's inside the box. Returns: [..., (y1, x1, y2, x2)] in pixel coordinates """ h, w = tf.split(tf.cast(shape, tf.float32), 2) scale = tf.concat([h, w, h, w], axis=-1) - tf.constant(1.0) shift = tf.constant([0., 0., 1., 1.]) return tf.cast(tf.round(tf.multiply(boxes, scale) + shift), tf.int32) ================================================ FILE: Mask_RCNN/mrcnn/parallel_model.py ================================================ """ Mask R-CNN Multi-GPU Support for Keras. Copyright (c) 2017 Matterport, Inc. Licensed under the MIT License (see LICENSE for details) Written by Waleed Abdulla Ideas and a small code snippets from these sources: https://github.com/fchollet/keras/issues/2436 https://medium.com/@kuza55/transparent-multi-gpu-training-on-tensorflow-with-keras-8b0016fd9012 https://github.com/avolkov1/keras_experiments/blob/master/keras_exp/multigpu/ https://github.com/fchollet/keras/blob/master/keras/utils/training_utils.py """ import tensorflow as tf import keras.backend as K import keras.layers as KL import keras.models as KM class ParallelModel(KM.Model): """Subclasses the standard Keras Model and adds multi-GPU support. It works by creating a copy of the model on each GPU. Then it slices the inputs and sends a slice to each copy of the model, and then merges the outputs together and applies the loss on the combined outputs. """ def __init__(self, keras_model, gpu_count): """Class constructor. keras_model: The Keras model to parallelize gpu_count: Number of GPUs. Must be > 1 """ self.inner_model = keras_model self.gpu_count = gpu_count merged_outputs = self.make_parallel() super(ParallelModel, self).__init__(inputs=self.inner_model.inputs, outputs=merged_outputs) def __getattribute__(self, attrname): """Redirect loading and saving methods to the inner model. That's where the weights are stored.""" if 'load' in attrname or 'save' in attrname: return getattr(self.inner_model, attrname) return super(ParallelModel, self).__getattribute__(attrname) def summary(self, *args, **kwargs): """Override summary() to display summaries of both, the wrapper and inner models.""" super(ParallelModel, self).summary(*args, **kwargs) self.inner_model.summary(*args, **kwargs) def make_parallel(self): """Creates a new wrapper model that consists of multiple replicas of the original model placed on different GPUs. """ # Slice inputs. Slice inputs on the CPU to avoid sending a copy # of the full inputs to all GPUs. Saves on bandwidth and memory. input_slices = {name: tf.split(x, self.gpu_count) for name, x in zip(self.inner_model.input_names, self.inner_model.inputs)} output_names = self.inner_model.output_names outputs_all = [] for i in range(len(self.inner_model.outputs)): outputs_all.append([]) # Run the model call() on each GPU to place the ops there for i in range(self.gpu_count): with tf.device('/gpu:%d' % i): with tf.name_scope('tower_%d' % i): # Run a slice of inputs through this replica zipped_inputs = zip(self.inner_model.input_names, self.inner_model.inputs) inputs = [ KL.Lambda(lambda s: input_slices[name][i], output_shape=lambda s: (None,) + s[1:])(tensor) for name, tensor in zipped_inputs] # Create the model replica and get the outputs outputs = self.inner_model(inputs) if not isinstance(outputs, list): outputs = [outputs] # Save the outputs for merging back together later for l, o in enumerate(outputs): outputs_all[l].append(o) # Merge outputs on CPU with tf.device('/cpu:0'): merged = [] for outputs, name in zip(outputs_all, output_names): # Concatenate or average outputs? # Outputs usually have a batch dimension and we concatenate # across it. If they don't, then the output is likely a loss # or a metric value that gets averaged across the batch. # Keras expects losses and metrics to be scalars. if K.int_shape(outputs[0]) == (): # Average m = KL.Lambda(lambda o: tf.add_n(o) / len(outputs), name=name)(outputs) else: # Concatenate m = KL.Concatenate(axis=0, name=name)(outputs) merged.append(m) return merged if __name__ == "__main__": # Testing code below. It creates a simple model to train on MNIST and # tries to run it on 2 GPUs. It saves the graph so it can be viewed # in TensorBoard. Run it as: # # python3 parallel_model.py import os import numpy as np import keras.optimizers from keras.datasets import mnist from keras.preprocessing.image import ImageDataGenerator GPU_COUNT = 2 # Root directory of the project ROOT_DIR = os.path.abspath("../") # Directory to save logs and trained model MODEL_DIR = os.path.join(ROOT_DIR, "logs") def build_model(x_train, num_classes): # Reset default graph. Keras leaves old ops in the graph, # which are ignored for execution but clutter graph # visualization in TensorBoard. tf.reset_default_graph() inputs = KL.Input(shape=x_train.shape[1:], name="input_image") x = KL.Conv2D(32, (3, 3), activation='relu', padding="same", name="conv1")(inputs) x = KL.Conv2D(64, (3, 3), activation='relu', padding="same", name="conv2")(x) x = KL.MaxPooling2D(pool_size=(2, 2), name="pool1")(x) x = KL.Flatten(name="flat1")(x) x = KL.Dense(128, activation='relu', name="dense1")(x) x = KL.Dense(num_classes, activation='softmax', name="dense2")(x) return KM.Model(inputs, x, "digit_classifier_model") # Load MNIST Data (x_train, y_train), (x_test, y_test) = mnist.load_data() x_train = np.expand_dims(x_train, -1).astype('float32') / 255 x_test = np.expand_dims(x_test, -1).astype('float32') / 255 print('x_train shape:', x_train.shape) print('x_test shape:', x_test.shape) # Build data generator and model datagen = ImageDataGenerator() model = build_model(x_train, 10) # Add multi-GPU support. model = ParallelModel(model, GPU_COUNT) optimizer = keras.optimizers.SGD(lr=0.01, momentum=0.9, clipnorm=5.0) model.compile(loss='sparse_categorical_crossentropy', optimizer=optimizer, metrics=['accuracy']) model.summary() # Train model.fit_generator( datagen.flow(x_train, y_train, batch_size=64), steps_per_epoch=50, epochs=10, verbose=1, validation_data=(x_test, y_test), callbacks=[keras.callbacks.TensorBoard(log_dir=MODEL_DIR, write_graph=True)] ) ================================================ FILE: Mask_RCNN/mrcnn/utils.py ================================================ """ Mask R-CNN Common utility functions and classes. Copyright (c) 2017 Matterport, Inc. Licensed under the MIT License (see LICENSE for details) Written by Waleed Abdulla """ import sys import os import math import random import numpy as np import tensorflow as tf import scipy import skimage.color import skimage.io import skimage.transform import urllib.request import shutil import warnings from distutils.version import LooseVersion # URL from which to download the latest COCO trained weights COCO_MODEL_URL = "https://github.com/matterport/Mask_RCNN/releases/download/v2.0/mask_rcnn_coco.h5" ############################################################ # Bounding Boxes ############################################################ def extract_bboxes(mask): """Compute bounding boxes from masks. mask: [height, width, num_instances]. Mask pixels are either 1 or 0. Returns: bbox array [num_instances, (y1, x1, y2, x2)]. """ boxes = np.zeros([mask.shape[-1], 4], dtype=np.int32) for i in range(mask.shape[-1]): m = mask[:, :, i] # Bounding box. horizontal_indicies = np.where(np.any(m, axis=0))[0] vertical_indicies = np.where(np.any(m, axis=1))[0] if horizontal_indicies.shape[0]: x1, x2 = horizontal_indicies[[0, -1]] y1, y2 = vertical_indicies[[0, -1]] # x2 and y2 should not be part of the box. Increment by 1. x2 += 1 y2 += 1 else: # No mask for this instance. Might happen due to # resizing or cropping. Set bbox to zeros x1, x2, y1, y2 = 0, 0, 0, 0 boxes[i] = np.array([y1, x1, y2, x2]) return boxes.astype(np.int32) def compute_iou(box, boxes, box_area, boxes_area): """Calculates IoU of the given box with the array of the given boxes. box: 1D vector [y1, x1, y2, x2] boxes: [boxes_count, (y1, x1, y2, x2)] box_area: float. the area of 'box' boxes_area: array of length boxes_count. Note: the areas are passed in rather than calculated here for efficiency. Calculate once in the caller to avoid duplicate work. """ # Calculate intersection areas y1 = np.maximum(box[0], boxes[:, 0]) y2 = np.minimum(box[2], boxes[:, 2]) x1 = np.maximum(box[1], boxes[:, 1]) x2 = np.minimum(box[3], boxes[:, 3]) intersection = np.maximum(x2 - x1, 0) * np.maximum(y2 - y1, 0) union = box_area + boxes_area[:] - intersection[:] iou = intersection / union return iou def compute_overlaps(boxes1, boxes2): """Computes IoU overlaps between two sets of boxes. boxes1, boxes2: [N, (y1, x1, y2, x2)]. For better performance, pass the largest set first and the smaller second. """ # Areas of anchors and GT boxes area1 = (boxes1[:, 2] - boxes1[:, 0]) * (boxes1[:, 3] - boxes1[:, 1]) area2 = (boxes2[:, 2] - boxes2[:, 0]) * (boxes2[:, 3] - boxes2[:, 1]) # Compute overlaps to generate matrix [boxes1 count, boxes2 count] # Each cell contains the IoU value. overlaps = np.zeros((boxes1.shape[0], boxes2.shape[0])) for i in range(overlaps.shape[1]): box2 = boxes2[i] overlaps[:, i] = compute_iou(box2, boxes1, area2[i], area1) return overlaps def compute_overlaps_masks(masks1, masks2): """Computes IoU overlaps between two sets of masks. masks1, masks2: [Height, Width, instances] """ # If either set of masks is empty return empty result if masks1.shape[0] == 0 or masks2.shape[0] == 0: return np.zeros((masks1.shape[0], masks2.shape[-1])) # flatten masks and compute their areas masks1 = np.reshape(masks1 > .5, (-1, masks1.shape[-1])).astype(np.float32) masks2 = np.reshape(masks2 > .5, (-1, masks2.shape[-1])).astype(np.float32) area1 = np.sum(masks1, axis=0) area2 = np.sum(masks2, axis=0) # intersections and union intersections = np.dot(masks1.T, masks2) union = area1[:, None] + area2[None, :] - intersections overlaps = intersections / union return overlaps def non_max_suppression(boxes, scores, threshold): """Performs non-maximum suppression and returns indices of kept boxes. boxes: [N, (y1, x1, y2, x2)]. Notice that (y2, x2) lays outside the box. scores: 1-D array of box scores. threshold: Float. IoU threshold to use for filtering. """ assert boxes.shape[0] > 0 if boxes.dtype.kind != "f": boxes = boxes.astype(np.float32) # Compute box areas y1 = boxes[:, 0] x1 = boxes[:, 1] y2 = boxes[:, 2] x2 = boxes[:, 3] area = (y2 - y1) * (x2 - x1) # Get indicies of boxes sorted by scores (highest first) ixs = scores.argsort()[::-1] pick = [] while len(ixs) > 0: # Pick top box and add its index to the list i = ixs[0] pick.append(i) # Compute IoU of the picked box with the rest iou = compute_iou(boxes[i], boxes[ixs[1:]], area[i], area[ixs[1:]]) # Identify boxes with IoU over the threshold. This # returns indices into ixs[1:], so add 1 to get # indices into ixs. remove_ixs = np.where(iou > threshold)[0] + 1 # Remove indices of the picked and overlapped boxes. ixs = np.delete(ixs, remove_ixs) ixs = np.delete(ixs, 0) return np.array(pick, dtype=np.int32) def apply_box_deltas(boxes, deltas): """Applies the given deltas to the given boxes. boxes: [N, (y1, x1, y2, x2)]. Note that (y2, x2) is outside the box. deltas: [N, (dy, dx, log(dh), log(dw))] """ boxes = boxes.astype(np.float32) # Convert to y, x, h, w height = boxes[:, 2] - boxes[:, 0] width = boxes[:, 3] - boxes[:, 1] center_y = boxes[:, 0] + 0.5 * height center_x = boxes[:, 1] + 0.5 * width # Apply deltas center_y += deltas[:, 0] * height center_x += deltas[:, 1] * width height *= np.exp(deltas[:, 2]) width *= np.exp(deltas[:, 3]) # Convert back to y1, x1, y2, x2 y1 = center_y - 0.5 * height x1 = center_x - 0.5 * width y2 = y1 + height x2 = x1 + width return np.stack([y1, x1, y2, x2], axis=1) def box_refinement_graph(box, gt_box): """Compute refinement needed to transform box to gt_box. box and gt_box are [N, (y1, x1, y2, x2)] """ box = tf.cast(box, tf.float32) gt_box = tf.cast(gt_box, tf.float32) height = box[:, 2] - box[:, 0] width = box[:, 3] - box[:, 1] center_y = box[:, 0] + 0.5 * height center_x = box[:, 1] + 0.5 * width gt_height = gt_box[:, 2] - gt_box[:, 0] gt_width = gt_box[:, 3] - gt_box[:, 1] gt_center_y = gt_box[:, 0] + 0.5 * gt_height gt_center_x = gt_box[:, 1] + 0.5 * gt_width dy = (gt_center_y - center_y) / height dx = (gt_center_x - center_x) / width dh = tf.log(gt_height / height) dw = tf.log(gt_width / width) result = tf.stack([dy, dx, dh, dw], axis=1) return result def box_refinement(box, gt_box): """Compute refinement needed to transform box to gt_box. box and gt_box are [N, (y1, x1, y2, x2)]. (y2, x2) is assumed to be outside the box. """ box = box.astype(np.float32) gt_box = gt_box.astype(np.float32) height = box[:, 2] - box[:, 0] width = box[:, 3] - box[:, 1] center_y = box[:, 0] + 0.5 * height center_x = box[:, 1] + 0.5 * width gt_height = gt_box[:, 2] - gt_box[:, 0] gt_width = gt_box[:, 3] - gt_box[:, 1] gt_center_y = gt_box[:, 0] + 0.5 * gt_height gt_center_x = gt_box[:, 1] + 0.5 * gt_width dy = (gt_center_y - center_y) / height dx = (gt_center_x - center_x) / width dh = np.log(gt_height / height) dw = np.log(gt_width / width) return np.stack([dy, dx, dh, dw], axis=1) ############################################################ # Dataset ############################################################ class Dataset(object): """The base class for dataset classes. To use it, create a new class that adds functions specific to the dataset you want to use. For example: class CatsAndDogsDataset(Dataset): def load_cats_and_dogs(self): ... def load_mask(self, image_id): ... def image_reference(self, image_id): ... See COCODataset and ShapesDataset as examples. """ def __init__(self, class_map=None): self._image_ids = [] self.image_info = [] # Background is always the first class self.class_info = [{"source": "", "id": 0, "name": "BG"}] self.source_class_ids = {} def add_class(self, source, class_id, class_name): assert "." not in source, "Source name cannot contain a dot" # Does the class exist already? for info in self.class_info: if info['source'] == source and info["id"] == class_id: # source.class_id combination already available, skip return # Add the class self.class_info.append({ "source": source, "id": class_id, "name": class_name, }) def add_image(self, source, image_id, path, **kwargs): image_info = { "id": image_id, "source": source, "path": path, } image_info.update(kwargs) self.image_info.append(image_info) def image_reference(self, image_id): """Return a link to the image in its source Website or details about the image that help looking it up or debugging it. Override for your dataset, but pass to this function if you encounter images not in your dataset. """ return "" def prepare(self, class_map=None): """Prepares the Dataset class for use. TODO: class map is not supported yet. When done, it should handle mapping classes from different datasets to the same class ID. """ def clean_name(name): """Returns a shorter version of object names for cleaner display.""" return ",".join(name.split(",")[:1]) # Build (or rebuild) everything else from the info dicts. self.num_classes = len(self.class_info) #print ("num_classes ") #print num_classes self.class_ids = np.arange(self.num_classes) self.class_names = [clean_name(c["name"]) for c in self.class_info] self.num_images = len(self.image_info) self._image_ids = np.arange(self.num_images) # Mapping from source class and image IDs to internal IDs self.class_from_source_map = {"{}.{}".format(info['source'], info['id']): id for info, id in zip(self.class_info, self.class_ids)} self.image_from_source_map = {"{}.{}".format(info['source'], info['id']): id for info, id in zip(self.image_info, self.image_ids)} # Map sources to class_ids they support self.sources = list(set([i['source'] for i in self.class_info])) self.source_class_ids = {} # Loop over datasets for source in self.sources: self.source_class_ids[source] = [] # Find classes that belong to this dataset for i, info in enumerate(self.class_info): # Include BG class in all datasets if i == 0 or source == info['source']: self.source_class_ids[source].append(i) def map_source_class_id(self, source_class_id): """Takes a source class ID and returns the int class ID assigned to it. For example: dataset.map_source_class_id("coco.12") -> 23 """ return self.class_from_source_map[source_class_id] def get_source_class_id(self, class_id, source): """Map an internal class ID to the corresponding class ID in the source dataset.""" info = self.class_info[class_id] assert info['source'] == source return info['id'] @property def image_ids(self): return self._image_ids def source_image_link(self, image_id): """Returns the path or URL to the image. Override this to return a URL to the image if it's available online for easy debugging. """ return self.image_info[image_id]["path"] def load_image(self, image_id): """Load the specified image and return a [H,W,3] Numpy array. """ # Load image image = skimage.io.imread(self.image_info[image_id]['path']) # If grayscale. Convert to RGB for consistency. if image.ndim != 3: image = skimage.color.gray2rgb(image) # If has an alpha channel, remove it for consistency if image.shape[-1] == 4: image = image[..., :3] return image def load_mask(self, image_id): """Load instance masks for the given image. Different datasets use different ways to store masks. Override this method to load instance masks and return them in the form of am array of binary masks of shape [height, width, instances]. Returns: masks: A bool array of shape [height, width, instance count] with a binary mask per instance. class_ids: a 1D array of class IDs of the instance masks. """ # Override this function to load a mask from your dataset. # Otherwise, it returns an empty mask. mask = np.empty([0, 0, 0]) class_ids = np.empty([0], np.int32) return mask, class_ids def resize_image(image, min_dim=None, max_dim=None, min_scale=None, mode="square"): """Resizes an image keeping the aspect ratio unchanged. min_dim: if provided, resizes the image such that it's smaller dimension == min_dim max_dim: if provided, ensures that the image longest side doesn't exceed this value. min_scale: if provided, ensure that the image is scaled up by at least this percent even if min_dim doesn't require it. mode: Resizing mode. none: No resizing. Return the image unchanged. square: Resize and pad with zeros to get a square image of size [max_dim, max_dim]. pad64: Pads width and height with zeros to make them multiples of 64. If min_dim or min_scale are provided, it scales the image up before padding. max_dim is ignored in this mode. The multiple of 64 is needed to ensure smooth scaling of feature maps up and down the 6 levels of the FPN pyramid (2**6=64). crop: Picks random crops from the image. First, scales the image based on min_dim and min_scale, then picks a random crop of size min_dim x min_dim. Can be used in training only. max_dim is not used in this mode. Returns: image: the resized image window: (y1, x1, y2, x2). If max_dim is provided, padding might be inserted in the returned image. If so, this window is the coordinates of the image part of the full image (excluding the padding). The x2, y2 pixels are not included. scale: The scale factor used to resize the image padding: Padding added to the image [(top, bottom), (left, right), (0, 0)] """ # Keep track of image dtype and return results in the same dtype image_dtype = image.dtype # Default window (y1, x1, y2, x2) and default scale == 1. h, w = image.shape[:2] window = (0, 0, h, w) scale = 1 padding = [(0, 0), (0, 0), (0, 0)] crop = None if mode == "none": return image, window, scale, padding, crop # Scale? if min_dim: # Scale up but not down scale = max(1, min_dim / min(h, w)) if min_scale and scale < min_scale: scale = min_scale # Does it exceed max dim? if max_dim and mode == "square": image_max = max(h, w) if round(image_max * scale) > max_dim: scale = max_dim / image_max # Resize image using bilinear interpolation if scale != 1: image = resize(image, (round(h * scale), round(w * scale)), preserve_range=True) # Need padding or cropping? if mode == "square": # Get new height and width h, w = image.shape[:2] top_pad = (max_dim - h) // 2 bottom_pad = max_dim - h - top_pad left_pad = (max_dim - w) // 2 right_pad = max_dim - w - left_pad padding = [(top_pad, bottom_pad), (left_pad, right_pad), (0, 0)] image = np.pad(image, padding, mode='constant', constant_values=0) window = (top_pad, left_pad, h + top_pad, w + left_pad) elif mode == "pad64": h, w = image.shape[:2] # Both sides must be divisible by 64 assert min_dim % 64 == 0, "Minimum dimension must be a multiple of 64" # Height if h % 64 > 0: max_h = h - (h % 64) + 64 top_pad = (max_h - h) // 2 bottom_pad = max_h - h - top_pad else: top_pad = bottom_pad = 0 # Width if w % 64 > 0: max_w = w - (w % 64) + 64 left_pad = (max_w - w) // 2 right_pad = max_w - w - left_pad else: left_pad = right_pad = 0 padding = [(top_pad, bottom_pad), (left_pad, right_pad), (0, 0)] image = np.pad(image, padding, mode='constant', constant_values=0) window = (top_pad, left_pad, h + top_pad, w + left_pad) elif mode == "crop": # Pick a random crop h, w = image.shape[:2] y = random.randint(0, (h - min_dim)) x = random.randint(0, (w - min_dim)) crop = (y, x, min_dim, min_dim) image = image[y:y + min_dim, x:x + min_dim] window = (0, 0, min_dim, min_dim) else: raise Exception("Mode {} not supported".format(mode)) return image.astype(image_dtype), window, scale, padding, crop def resize_mask(mask, scale, padding, crop=None): """Resizes a mask using the given scale and padding. Typically, you get the scale and padding from resize_image() to ensure both, the image and the mask, are resized consistently. scale: mask scaling factor padding: Padding to add to the mask in the form [(top, bottom), (left, right), (0, 0)] """ # Suppress warning from scipy 0.13.0, the output shape of zoom() is # calculated with round() instead of int() with warnings.catch_warnings(): warnings.simplefilter("ignore") mask = scipy.ndimage.zoom(mask, zoom=[scale, scale, 1], order=0) if crop is not None: y, x, h, w = crop mask = mask[y:y + h, x:x + w] else: mask = np.pad(mask, padding, mode='constant', constant_values=0) return mask def minimize_mask(bbox, mask, mini_shape): """Resize masks to a smaller version to reduce memory load. Mini-masks can be resized back to image scale using expand_masks() See inspect_data.ipynb notebook for more details. """ mini_mask = np.zeros(mini_shape + (mask.shape[-1],), dtype=bool) for i in range(mask.shape[-1]): # Pick slice and cast to bool in case load_mask() returned wrong dtype m = mask[:, :, i].astype(bool) y1, x1, y2, x2 = bbox[i][:4] m = m[y1:y2, x1:x2] if m.size == 0: raise Exception("Invalid bounding box with area of zero") # Resize with bilinear interpolation m = resize(m, mini_shape) mini_mask[:, :, i] = np.around(m).astype(np.bool) return mini_mask def expand_mask(bbox, mini_mask, image_shape): """Resizes mini masks back to image size. Reverses the change of minimize_mask(). See inspect_data.ipynb notebook for more details. """ mask = np.zeros(image_shape[:2] + (mini_mask.shape[-1],), dtype=bool) for i in range(mask.shape[-1]): m = mini_mask[:, :, i] y1, x1, y2, x2 = bbox[i][:4] h = y2 - y1 w = x2 - x1 # Resize with bilinear interpolation m = resize(m, (h, w)) mask[y1:y2, x1:x2, i] = np.around(m).astype(np.bool) return mask # TODO: Build and use this function to reduce code duplication def mold_mask(mask, config): pass def unmold_mask(mask, bbox, image_shape): """Converts a mask generated by the neural network to a format similar to its original shape. mask: [height, width] of type float. A small, typically 28x28 mask. bbox: [y1, x1, y2, x2]. The box to fit the mask in. Returns a binary mask with the same size as the original image. """ threshold = 0.5 y1, x1, y2, x2 = bbox mask = resize(mask, (y2 - y1, x2 - x1)) mask = np.where(mask >= threshold, 1, 0).astype(np.bool) # Put the mask in the right location. full_mask = np.zeros(image_shape[:2], dtype=np.bool) full_mask[y1:y2, x1:x2] = mask return full_mask ############################################################ # Anchors ############################################################ def generate_anchors(scales, ratios, shape, feature_stride, anchor_stride): """ scales: 1D array of anchor sizes in pixels. Example: [32, 64, 128] ratios: 1D array of anchor ratios of width/height. Example: [0.5, 1, 2] shape: [height, width] spatial shape of the feature map over which to generate anchors. feature_stride: Stride of the feature map relative to the image in pixels. anchor_stride: Stride of anchors on the feature map. For example, if the value is 2 then generate anchors for every other feature map pixel. """ # Get all combinations of scales and ratios scales, ratios = np.meshgrid(np.array(scales), np.array(ratios)) scales = scales.flatten() ratios = ratios.flatten() # Enumerate heights and widths from scales and ratios heights = scales / np.sqrt(ratios) widths = scales * np.sqrt(ratios) # Enumerate shifts in feature space shifts_y = np.arange(0, shape[0], anchor_stride) * feature_stride shifts_x = np.arange(0, shape[1], anchor_stride) * feature_stride shifts_x, shifts_y = np.meshgrid(shifts_x, shifts_y) # Enumerate combinations of shifts, widths, and heights box_widths, box_centers_x = np.meshgrid(widths, shifts_x) box_heights, box_centers_y = np.meshgrid(heights, shifts_y) # Reshape to get a list of (y, x) and a list of (h, w) box_centers = np.stack( [box_centers_y, box_centers_x], axis=2).reshape([-1, 2]) box_sizes = np.stack([box_heights, box_widths], axis=2).reshape([-1, 2]) # Convert to corner coordinates (y1, x1, y2, x2) boxes = np.concatenate([box_centers - 0.5 * box_sizes, box_centers + 0.5 * box_sizes], axis=1) return boxes def generate_pyramid_anchors(scales, ratios, feature_shapes, feature_strides, anchor_stride): """Generate anchors at different levels of a feature pyramid. Each scale is associated with a level of the pyramid, but each ratio is used in all levels of the pyramid. Returns: anchors: [N, (y1, x1, y2, x2)]. All generated anchors in one array. Sorted with the same order of the given scales. So, anchors of scale[0] come first, then anchors of scale[1], and so on. """ # Anchors # [anchor_count, (y1, x1, y2, x2)] anchors = [] for i in range(len(scales)): anchors.append(generate_anchors(scales[i], ratios, feature_shapes[i], feature_strides[i], anchor_stride)) return np.concatenate(anchors, axis=0) ############################################################ # Miscellaneous ############################################################ def trim_zeros(x): """It's common to have tensors larger than the available data and pad with zeros. This function removes rows that are all zeros. x: [rows, columns]. """ assert len(x.shape) == 2 return x[~np.all(x == 0, axis=1)] def compute_matches(gt_boxes, gt_class_ids, gt_masks, pred_boxes, pred_class_ids, pred_scores, pred_masks, iou_threshold=0.5, score_threshold=0.0): """Finds matches between prediction and ground truth instances. Returns: gt_match: 1-D array. For each GT box it has the index of the matched predicted box. pred_match: 1-D array. For each predicted box, it has the index of the matched ground truth box. overlaps: [pred_boxes, gt_boxes] IoU overlaps. """ # Trim zero padding # TODO: cleaner to do zero unpadding upstream gt_boxes = trim_zeros(gt_boxes) gt_masks = gt_masks[..., :gt_boxes.shape[0]] pred_boxes = trim_zeros(pred_boxes) pred_scores = pred_scores[:pred_boxes.shape[0]] # Sort predictions by score from high to low indices = np.argsort(pred_scores)[::-1] pred_boxes = pred_boxes[indices] pred_class_ids = pred_class_ids[indices] pred_scores = pred_scores[indices] pred_masks = pred_masks[..., indices] # Compute IoU overlaps [pred_masks, gt_masks] overlaps = compute_overlaps_masks(pred_masks, gt_masks) # Loop through predictions and find matching ground truth boxes match_count = 0 pred_match = -1 * np.ones([pred_boxes.shape[0]]) gt_match = -1 * np.ones([gt_boxes.shape[0]]) for i in range(len(pred_boxes)): # Find best matching ground truth box # 1. Sort matches by score sorted_ixs = np.argsort(overlaps[i])[::-1] # 2. Remove low scores low_score_idx = np.where(overlaps[i, sorted_ixs] < score_threshold)[0] if low_score_idx.size > 0: sorted_ixs = sorted_ixs[:low_score_idx[0]] # 3. Find the match for j in sorted_ixs: # If ground truth box is already matched, go to next one if gt_match[j] > 0: continue # If we reach IoU smaller than the threshold, end the loop iou = overlaps[i, j] if iou < iou_threshold: break # Do we have a match? if pred_class_ids[i] == gt_class_ids[j]: match_count += 1 gt_match[j] = i pred_match[i] = j break return gt_match, pred_match, overlaps def compute_ap(gt_boxes, gt_class_ids, gt_masks, pred_boxes, pred_class_ids, pred_scores, pred_masks, iou_threshold=0.5): """Compute Average Precision at a set IoU threshold (default 0.5). Returns: mAP: Mean Average Precision precisions: List of precisions at different class score thresholds. recalls: List of recall values at different class score thresholds. overlaps: [pred_boxes, gt_boxes] IoU overlaps. """ # Get matches and overlaps gt_match, pred_match, overlaps = compute_matches( gt_boxes, gt_class_ids, gt_masks, pred_boxes, pred_class_ids, pred_scores, pred_masks, iou_threshold) # Compute precision and recall at each prediction box step precisions = np.cumsum(pred_match > -1) / (np.arange(len(pred_match)) + 1) recalls = np.cumsum(pred_match > -1).astype(np.float32) / len(gt_match) # Pad with start and end values to simplify the math precisions = np.concatenate([[0], precisions, [0]]) recalls = np.concatenate([[0], recalls, [1]]) # Ensure precision values decrease but don't increase. This way, the # precision value at each recall threshold is the maximum it can be # for all following recall thresholds, as specified by the VOC paper. for i in range(len(precisions) - 2, -1, -1): precisions[i] = np.maximum(precisions[i], precisions[i + 1]) # Compute mean AP over recall range indices = np.where(recalls[:-1] != recalls[1:])[0] + 1 mAP = np.sum((recalls[indices] - recalls[indices - 1]) * precisions[indices]) return mAP, precisions, recalls, overlaps def compute_ap_range(gt_box, gt_class_id, gt_mask, pred_box, pred_class_id, pred_score, pred_mask, iou_thresholds=None, verbose=1): """Compute AP over a range or IoU thresholds. Default range is 0.5-0.95.""" # Default is 0.5 to 0.95 with increments of 0.05 iou_thresholds = iou_thresholds or np.arange(0.5, 1.0, 0.05) # Compute AP over range of IoU thresholds AP = [] for iou_threshold in iou_thresholds: ap, precisions, recalls, overlaps =\ compute_ap(gt_box, gt_class_id, gt_mask, pred_box, pred_class_id, pred_score, pred_mask, iou_threshold=iou_threshold) if verbose: print("AP @{:.2f}:\t {:.3f}".format(iou_threshold, ap)) AP.append(ap) AP = np.array(AP).mean() if verbose: print("AP @{:.2f}-{:.2f}:\t {:.3f}".format( iou_thresholds[0], iou_thresholds[-1], AP)) return AP def compute_recall(pred_boxes, gt_boxes, iou): """Compute the recall at the given IoU threshold. It's an indication of how many GT boxes were found by the given prediction boxes. pred_boxes: [N, (y1, x1, y2, x2)] in image coordinates gt_boxes: [N, (y1, x1, y2, x2)] in image coordinates """ # Measure overlaps overlaps = compute_overlaps(pred_boxes, gt_boxes) iou_max = np.max(overlaps, axis=1) iou_argmax = np.argmax(overlaps, axis=1) positive_ids = np.where(iou_max >= iou)[0] matched_gt_boxes = iou_argmax[positive_ids] recall = len(set(matched_gt_boxes)) / gt_boxes.shape[0] return recall, positive_ids # ## Batch Slicing # Some custom layers support a batch size of 1 only, and require a lot of work # to support batches greater than 1. This function slices an input tensor # across the batch dimension and feeds batches of size 1. Effectively, # an easy way to support batches > 1 quickly with little code modification. # In the long run, it's more efficient to modify the code to support large # batches and getting rid of this function. Consider this a temporary solution def batch_slice(inputs, graph_fn, batch_size, names=None): """Splits inputs into slices and feeds each slice to a copy of the given computation graph and then combines the results. It allows you to run a graph on a batch of inputs even if the graph is written to support one instance only. inputs: list of tensors. All must have the same first dimension length graph_fn: A function that returns a TF tensor that's part of a graph. batch_size: number of slices to divide the data into. names: If provided, assigns names to the resulting tensors. """ if not isinstance(inputs, list): inputs = [inputs] outputs = [] for i in range(batch_size): inputs_slice = [x[i] for x in inputs] output_slice = graph_fn(*inputs_slice) if not isinstance(output_slice, (tuple, list)): output_slice = [output_slice] outputs.append(output_slice) # Change outputs from a list of slices where each is # a list of outputs to a list of outputs and each has # a list of slices outputs = list(zip(*outputs)) if names is None: names = [None] * len(outputs) result = [tf.stack(o, axis=0, name=n) for o, n in zip(outputs, names)] if len(result) == 1: result = result[0] return result def download_trained_weights(coco_model_path, verbose=1): """Download COCO trained weights from Releases. coco_model_path: local path of COCO trained weights """ if verbose > 0: print("Downloading pretrained model to " + coco_model_path + " ...") with urllib.request.urlopen(COCO_MODEL_URL) as resp, open(coco_model_path, 'wb') as out: shutil.copyfileobj(resp, out) if verbose > 0: print("... done downloading pretrained model!") def norm_boxes(boxes, shape): """Converts boxes from pixel coordinates to normalized coordinates. boxes: [N, (y1, x1, y2, x2)] in pixel coordinates shape: [..., (height, width)] in pixels Note: In pixel coordinates (y2, x2) is outside the box. But in normalized coordinates it's inside the box. Returns: [N, (y1, x1, y2, x2)] in normalized coordinates """ h, w = shape scale = np.array([h - 1, w - 1, h - 1, w - 1]) shift = np.array([0, 0, 1, 1]) return np.divide((boxes - shift), scale).astype(np.float32) def denorm_boxes(boxes, shape): """Converts boxes from normalized coordinates to pixel coordinates. boxes: [N, (y1, x1, y2, x2)] in normalized coordinates shape: [..., (height, width)] in pixels Note: In pixel coordinates (y2, x2) is outside the box. But in normalized coordinates it's inside the box. Returns: [N, (y1, x1, y2, x2)] in pixel coordinates """ h, w = shape scale = np.array([h - 1, w - 1, h - 1, w - 1]) shift = np.array([0, 0, 1, 1]) return np.around(np.multiply(boxes, scale) + shift).astype(np.int32) def resize(image, output_shape, order=1, mode='constant', cval=0, clip=True, preserve_range=False, anti_aliasing=False, anti_aliasing_sigma=None): """A wrapper for Scikit-Image resize(). Scikit-Image generates warnings on every call to resize() if it doesn't receive the right parameters. The right parameters depend on the version of skimage. This solves the problem by using different parameters per version. And it provides a central place to control resizing defaults. """ if LooseVersion(skimage.__version__) >= LooseVersion("0.14"): # New in 0.14: anti_aliasing. Default it to False for backward # compatibility with skimage 0.13. return skimage.transform.resize( image, output_shape, order=order, mode=mode, cval=cval, clip=clip, preserve_range=preserve_range, anti_aliasing=anti_aliasing, anti_aliasing_sigma=anti_aliasing_sigma) else: return skimage.transform.resize( image, output_shape, order=order, mode=mode, cval=cval, clip=clip, preserve_range=preserve_range) ================================================ FILE: Mask_RCNN/mrcnn/visualize.py ================================================ """ Mask R-CNN Display and Visualization Functions. Copyright (c) 2017 Matterport, Inc. Licensed under the MIT License (see LICENSE for details) Written by Waleed Abdulla """ import os import sys import random import itertools import colorsys import numpy as np from skimage.measure import find_contours import matplotlib.pyplot as plt from matplotlib import patches, lines from matplotlib.patches import Polygon import IPython.display # Root directory of the project ROOT_DIR = os.path.abspath("../") # Import Mask RCNN sys.path.append(ROOT_DIR) # To find local version of the library from mrcnn import utils ############################################################ # Visualization ############################################################ def display_images(images, titles=None, cols=4, cmap=None, norm=None, interpolation=None): """Display the given set of images, optionally with titles. images: list or array of image tensors in HWC format. titles: optional. A list of titles to display with each image. cols: number of images per row cmap: Optional. Color map to use. For example, "Blues". norm: Optional. A Normalize instance to map values to colors. interpolation: Optional. Image interpolation to use for display. """ titles = titles if titles is not None else [""] * len(images) rows = len(images) // cols + 1 plt.figure(figsize=(14, 14 * rows // cols)) i = 1 for image, title in zip(images, titles): plt.subplot(rows, cols, i) plt.title(title, fontsize=9) plt.axis('off') plt.imshow(image.astype(np.uint8), cmap=cmap, norm=norm, interpolation=interpolation) i += 1 plt.show() def random_colors(N, bright=True): """ Generate random colors. To get visually distinct colors, generate them in HSV space then convert to RGB. """ brightness = 1.0 if bright else 0.7 hsv = [(i / N, 1, brightness) for i in range(N)] colors = list(map(lambda c: colorsys.hsv_to_rgb(*c), hsv)) random.shuffle(colors) return colors def apply_mask(image, mask, color, alpha=0.5): """Apply the given mask to the image. """ for c in range(3): image[:, :, c] = np.where(mask == 1, image[:, :, c] * (1 - alpha) + alpha * color[c] * 255, image[:, :, c]) return image def display_instances(image, boxes, masks, class_ids, class_names, scores=None, title="", figsize=(16, 16), ax=None, show_mask=True, show_bbox=True, colors=None, captions=None): """ boxes: [num_instance, (y1, x1, y2, x2, class_id)] in image coordinates. masks: [height, width, num_instances] class_ids: [num_instances] class_names: list of class names of the dataset scores: (optional) confidence scores for each box title: (optional) Figure title show_mask, show_bbox: To show masks and bounding boxes or not figsize: (optional) the size of the image colors: (optional) An array or colors to use with each object captions: (optional) A list of strings to use as captions for each object """ # Number of instances N = boxes.shape[0] if not N: print("\n*** No instances to display *** \n") else: assert boxes.shape[0] == masks.shape[-1] == class_ids.shape[0] # If no axis is passed, create one and automatically call show() auto_show = False if not ax: _, ax = plt.subplots(1, figsize=figsize) auto_show = True # Generate random colors colors = colors or random_colors(N) # Show area outside image boundaries. height, width = image.shape[:2] ax.set_ylim(height + 10, -10) ax.set_xlim(-10, width + 10) ax.axis('off') ax.set_title(title) masked_image = image.astype(np.uint32).copy() for i in range(N): color = colors[i] # Bounding box if not np.any(boxes[i]): # Skip this instance. Has no bbox. Likely lost in image cropping. continue y1, x1, y2, x2 = boxes[i] if show_bbox: p = patches.Rectangle((x1, y1), x2 - x1, y2 - y1, linewidth=2, alpha=0.7, linestyle="dashed", edgecolor=color, facecolor='none') ax.add_patch(p) # Label if not captions: class_id = class_ids[i] score = scores[i] if scores is not None else None label = class_names[class_id] x = random.randint(x1, (x1 + x2) // 2) caption = "{} {:.3f}".format(label, score) if score else label else: caption = captions[i] ax.text(x1, y1 + 8, caption, color='w', size=11, backgroundcolor="none") # Mask mask = masks[:, :, i] if show_mask: masked_image = apply_mask(masked_image, mask, color) # Mask Polygon # Pad to ensure proper polygons for masks that touch image edges. padded_mask = np.zeros( (mask.shape[0] + 2, mask.shape[1] + 2), dtype=np.uint8) padded_mask[1:-1, 1:-1] = mask contours = find_contours(padded_mask, 0.5) for verts in contours: # Subtract the padding and flip (y, x) to (x, y) verts = np.fliplr(verts) - 1 p = Polygon(verts, facecolor="none", edgecolor=color) ax.add_patch(p) ax.imshow(masked_image.astype(np.uint8)) if auto_show: plt.show() def display_differences(image, gt_box, gt_class_id, gt_mask, pred_box, pred_class_id, pred_score, pred_mask, class_names, title="", ax=None, show_mask=True, show_box=True, iou_threshold=0.5, score_threshold=0.5): """Display ground truth and prediction instances on the same image.""" # Match predictions to ground truth gt_match, pred_match, overlaps = utils.compute_matches( gt_box, gt_class_id, gt_mask, pred_box, pred_class_id, pred_score, pred_mask, iou_threshold=iou_threshold, score_threshold=score_threshold) # Ground truth = green. Predictions = red colors = [(0, 1, 0, .8)] * len(gt_match)\ + [(1, 0, 0, 1)] * len(pred_match) # Concatenate GT and predictions class_ids = np.concatenate([gt_class_id, pred_class_id]) scores = np.concatenate([np.zeros([len(gt_match)]), pred_score]) boxes = np.concatenate([gt_box, pred_box]) masks = np.concatenate([gt_mask, pred_mask], axis=-1) # Captions per instance show score/IoU captions = ["" for m in gt_match] + ["{:.2f} / {:.2f}".format( pred_score[i], (overlaps[i, int(pred_match[i])] if pred_match[i] > -1 else overlaps[i].max())) for i in range(len(pred_match))] # Set title if not provided title = title or "Ground Truth and Detections\n GT=green, pred=red, captions: score/IoU" # Display display_instances( image, boxes, masks, class_ids, class_names, scores, ax=ax, show_bbox=show_box, show_mask=show_mask, colors=colors, captions=captions, title=title) def draw_rois(image, rois, refined_rois, mask, class_ids, class_names, limit=10): """ anchors: [n, (y1, x1, y2, x2)] list of anchors in image coordinates. proposals: [n, 4] the same anchors but refined to fit objects better. """ masked_image = image.copy() # Pick random anchors in case there are too many. ids = np.arange(rois.shape[0], dtype=np.int32) ids = np.random.choice( ids, limit, replace=False) if ids.shape[0] > limit else ids fig, ax = plt.subplots(1, figsize=(12, 12)) if rois.shape[0] > limit: plt.title("Showing {} random ROIs out of {}".format( len(ids), rois.shape[0])) else: plt.title("{} ROIs".format(len(ids))) # Show area outside image boundaries. ax.set_ylim(image.shape[0] + 20, -20) ax.set_xlim(-50, image.shape[1] + 20) ax.axis('off') for i, id in enumerate(ids): color = np.random.rand(3) class_id = class_ids[id] # ROI y1, x1, y2, x2 = rois[id] p = patches.Rectangle((x1, y1), x2 - x1, y2 - y1, linewidth=2, edgecolor=color if class_id else "gray", facecolor='none', linestyle="dashed") ax.add_patch(p) # Refined ROI if class_id: ry1, rx1, ry2, rx2 = refined_rois[id] p = patches.Rectangle((rx1, ry1), rx2 - rx1, ry2 - ry1, linewidth=2, edgecolor=color, facecolor='none') ax.add_patch(p) # Connect the top-left corners of the anchor and proposal for easy visualization ax.add_line(lines.Line2D([x1, rx1], [y1, ry1], color=color)) # Label label = class_names[class_id] ax.text(rx1, ry1 + 8, "{}".format(label), color='w', size=11, backgroundcolor="none") # Mask m = utils.unmold_mask(mask[id], rois[id] [:4].astype(np.int32), image.shape) masked_image = apply_mask(masked_image, m, color) ax.imshow(masked_image) # Print stats print("Positive ROIs: ", class_ids[class_ids > 0].shape[0]) print("Negative ROIs: ", class_ids[class_ids == 0].shape[0]) print("Positive Ratio: {:.2f}".format( class_ids[class_ids > 0].shape[0] / class_ids.shape[0])) # TODO: Replace with matplotlib equivalent? def draw_box(image, box, color): """Draw 3-pixel width bounding boxes on the given image array. color: list of 3 int values for RGB. """ y1, x1, y2, x2 = box image[y1:y1 + 2, x1:x2] = color image[y2:y2 + 2, x1:x2] = color image[y1:y2, x1:x1 + 2] = color image[y1:y2, x2:x2 + 2] = color return image def display_top_masks(image, mask, class_ids, class_names, limit=4): """Display the given image and the top few class masks.""" to_display = [] titles = [] to_display.append(image) titles.append("H x W={}x{}".format(image.shape[0], image.shape[1])) # Pick top prominent classes in this image unique_class_ids = np.unique(class_ids) mask_area = [np.sum(mask[:, :, np.where(class_ids == i)[0]]) for i in unique_class_ids] top_ids = [v[0] for v in sorted(zip(unique_class_ids, mask_area), key=lambda r: r[1], reverse=True) if v[1] > 0] # Generate images and titles for i in range(limit): class_id = top_ids[i] if i < len(top_ids) else -1 # Pull masks of instances belonging to the same class. m = mask[:, :, np.where(class_ids == class_id)[0]] m = np.sum(m * np.arange(1, m.shape[-1] + 1), -1) to_display.append(m) titles.append(class_names[class_id] if class_id != -1 else "-") display_images(to_display, titles=titles, cols=limit + 1, cmap="Blues_r") def plot_precision_recall(AP, precisions, recalls): """Draw the precision-recall curve. AP: Average precision at IoU >= 0.5 precisions: list of precision values recalls: list of recall values """ # Plot the Precision-Recall curve _, ax = plt.subplots(1) ax.set_title("Precision-Recall Curve. AP@50 = {:.3f}".format(AP)) ax.set_ylim(0, 1.1) ax.set_xlim(0, 1.1) _ = ax.plot(recalls, precisions) def plot_overlaps(gt_class_ids, pred_class_ids, pred_scores, overlaps, class_names, threshold=0.5): """Draw a grid showing how ground truth objects are classified. gt_class_ids: [N] int. Ground truth class IDs pred_class_id: [N] int. Predicted class IDs pred_scores: [N] float. The probability scores of predicted classes overlaps: [pred_boxes, gt_boxes] IoU overlaps of predictions and GT boxes. class_names: list of all class names in the dataset threshold: Float. The prediction probability required to predict a class """ gt_class_ids = gt_class_ids[gt_class_ids != 0] pred_class_ids = pred_class_ids[pred_class_ids != 0] plt.figure(figsize=(12, 10)) plt.imshow(overlaps, interpolation='nearest', cmap=plt.cm.Blues) plt.yticks(np.arange(len(pred_class_ids)), ["{} ({:.2f})".format(class_names[int(id)], pred_scores[i]) for i, id in enumerate(pred_class_ids)]) plt.xticks(np.arange(len(gt_class_ids)), [class_names[int(id)] for id in gt_class_ids], rotation=90) thresh = overlaps.max() / 2. for i, j in itertools.product(range(overlaps.shape[0]), range(overlaps.shape[1])): text = "" if overlaps[i, j] > threshold: text = "match" if gt_class_ids[j] == pred_class_ids[i] else "wrong" color = ("white" if overlaps[i, j] > thresh else "black" if overlaps[i, j] > 0 else "grey") plt.text(j, i, "{:.3f}\n{}".format(overlaps[i, j], text), horizontalalignment="center", verticalalignment="center", fontsize=9, color=color) plt.tight_layout() plt.xlabel("Ground Truth") plt.ylabel("Predictions") def draw_boxes(image, boxes=None, refined_boxes=None, masks=None, captions=None, visibilities=None, title="", ax=None): """Draw bounding boxes and segmentation masks with different customizations. boxes: [N, (y1, x1, y2, x2, class_id)] in image coordinates. refined_boxes: Like boxes, but draw with solid lines to show that they're the result of refining 'boxes'. masks: [N, height, width] captions: List of N titles to display on each box visibilities: (optional) List of values of 0, 1, or 2. Determine how prominent each bounding box should be. title: An optional title to show over the image ax: (optional) Matplotlib axis to draw on. """ # Number of boxes assert boxes is not None or refined_boxes is not None N = boxes.shape[0] if boxes is not None else refined_boxes.shape[0] # Matplotlib Axis if not ax: _, ax = plt.subplots(1, figsize=(12, 12)) # Generate random colors colors = random_colors(N) # Show area outside image boundaries. margin = image.shape[0] // 10 ax.set_ylim(image.shape[0] + margin, -margin) ax.set_xlim(-margin, image.shape[1] + margin) ax.axis('off') ax.set_title(title) masked_image = image.astype(np.uint32).copy() for i in range(N): # Box visibility visibility = visibilities[i] if visibilities is not None else 1 if visibility == 0: color = "gray" style = "dotted" alpha = 0.5 elif visibility == 1: color = colors[i] style = "dotted" alpha = 1 elif visibility == 2: color = colors[i] style = "solid" alpha = 1 # Boxes if boxes is not None: if not np.any(boxes[i]): # Skip this instance. Has no bbox. Likely lost in cropping. continue y1, x1, y2, x2 = boxes[i] p = patches.Rectangle((x1, y1), x2 - x1, y2 - y1, linewidth=2, alpha=alpha, linestyle=style, edgecolor=color, facecolor='none') ax.add_patch(p) # Refined boxes if refined_boxes is not None and visibility > 0: ry1, rx1, ry2, rx2 = refined_boxes[i].astype(np.int32) p = patches.Rectangle((rx1, ry1), rx2 - rx1, ry2 - ry1, linewidth=2, edgecolor=color, facecolor='none') ax.add_patch(p) # Connect the top-left corners of the anchor and proposal if boxes is not None: ax.add_line(lines.Line2D([x1, rx1], [y1, ry1], color=color)) # Captions if captions is not None: caption = captions[i] # If there are refined boxes, display captions on them if refined_boxes is not None: y1, x1, y2, x2 = ry1, rx1, ry2, rx2 x = random.randint(x1, (x1 + x2) // 2) ax.text(x1, y1, caption, size=11, verticalalignment='top', color='w', backgroundcolor="none", bbox={'facecolor': color, 'alpha': 0.5, 'pad': 2, 'edgecolor': 'none'}) # Masks if masks is not None: mask = masks[:, :, i] masked_image = apply_mask(masked_image, mask, color) # Mask Polygon # Pad to ensure proper polygons for masks that touch image edges. padded_mask = np.zeros( (mask.shape[0] + 2, mask.shape[1] + 2), dtype=np.uint8) padded_mask[1:-1, 1:-1] = mask contours = find_contours(padded_mask, 0.5) for verts in contours: # Subtract the padding and flip (y, x) to (x, y) verts = np.fliplr(verts) - 1 p = Polygon(verts, facecolor="none", edgecolor=color) ax.add_patch(p) ax.imshow(masked_image.astype(np.uint8)) def display_table(table): """Display values in a table format. table: an iterable of rows, and each row is an iterable of values. """ html = "" for row in table: row_html = "" for col in row: row_html += "{:40}".format(str(col)) html += "" + row_html + "" html = "" + html + "
" IPython.display.display(IPython.display.HTML(html)) def display_weight_stats(model): """Scans all the weights in the model and returns a list of tuples that contain stats about each weight. """ layers = model.get_trainable_layers() table = [["WEIGHT NAME", "SHAPE", "MIN", "MAX", "STD"]] for l in layers: weight_values = l.get_weights() # list of Numpy arrays weight_tensors = l.weights # list of TF tensors for i, w in enumerate(weight_values): weight_name = weight_tensors[i].name # Detect problematic layers. Exclude biases of conv layers. alert = "" if w.min() == w.max() and not (l.__class__.__name__ == "Conv2D" and i == 1): alert += "*** dead?" if np.abs(w.min()) > 1000 or np.abs(w.max()) > 1000: alert += "*** Overflow?" # Add row table.append([ weight_name + alert, str(w.shape), "{:+9.4f}".format(w.min()), "{:+10.4f}".format(w.max()), "{:+9.4f}".format(w.std()), ]) display_table(table) ================================================ FILE: Mask_RCNN/requirements.txt ================================================ numpy scipy Pillow cython matplotlib scikit-image tensorflow-gpu==1.11 keras>=2.0.8 opencv-python h5py imgaug IPython[all] ================================================ FILE: Mask_RCNN/samples/warehouse/eval.py ================================================ """ Mask R-CNN Based on the work of Waleed Abdulla (Matterport) Modified by Dinh-Cuong Hoang ------------------------------------------------------------ python3 eval.py It will read rgb and ground-truth images from /rgb and gt/ folders in .../Object-RPE/data then save results in .../Object-RPE/data/mask """ import os import sys import json import datetime import numpy as np import skimage.draw import glob import matplotlib.pyplot as plt import matplotlib.image as mpimg # Root directory of the project ROOT_DIR = os.path.abspath("../../") # Import Mask RCNN sys.path.append(ROOT_DIR) # To find local version of the library from mrcnn.config import Config from mrcnn import model as modellib, utils # Path to trained weights file COCO_WEIGHTS_PATH = os.path.join(ROOT_DIR, "mask_rcnn_coco.h5") DEFAULT_LOGS_DIR = os.path.join(ROOT_DIR, "logs") class WarehouseConfig(Config): """Configuration for training on the toy dataset. Derives from the base Config class and overrides some values. """ # Give the configuration a recognizable name NAME = "Warehouse" # We use a GPU with 12GB memory, which can fit two images. # Adjust down if you use a smaller GPU. IMAGES_PER_GPU = 1 # Number of classes (including background) NUM_CLASSES = 1 + 13 # Background + objects # Number of training steps per epoch STEPS_PER_EPOCH = 400 # Skip detections with < 90% confidence DETECTION_MIN_CONFIDENCE = 0.6 def color_map(): color_map_dic = { 0: [0, 0, 0], 1: [128, 128, 0], 2: [ 0, 128, 128], 3: [128, 0, 128], 4: [128, 0, 0], 5: [ 0, 128, 0], 6: [ 0, 0, 128], 7: [255, 255, 0], 8: [255, 0, 255], 9: [ 0, 255, 255], 10: [255, 0, 0], 11: [ 0, 255, 0], 12: [ 0, 0, 255], 13: [ 92, 112, 92], 14: [ 0, 0, 70], 15: [ 0, 60, 100], 16: [ 0, 80, 100], 17: [ 0, 0, 230], 18: [119, 11, 32], 19: [ 0, 0, 121] } return color_map_dic def get_masks(image, mask, class_ids): gray = skimage.color.gray2rgb(skimage.color.rgb2gray(image)) * 255 instance_masks = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) semantic_masks = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) if mask.shape[-1] > 0: mask_zero = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) for i in range(mask.shape[-1]): semantic_mask_one = np.ones((image.shape[0], image.shape[1]), dtype=np.uint8) semantic_mask_one = semantic_mask_one * class_ids[i] semantic_masks = np.where(mask[:, :, i], semantic_mask_one, semantic_masks).astype(np.uint8) instance_mask_one = np.ones((image.shape[0], image.shape[1]), dtype=np.uint8) instance_mask_one = instance_mask_one * (i+1) instance_masks = np.where(mask[:, :, i], instance_mask_one, instance_masks).astype(np.uint8) instance_to_color = color_map() color_masks = np.zeros((image.shape[0], image.shape[1], 3), dtype=np.uint8) for key in instance_to_color.keys(): color_masks[instance_masks == key] = instance_to_color[key] return semantic_masks, instance_masks, color_masks def detect_and_get_masks(model): data_dir = os.path.abspath("../../../") + '/data/' rgb_dir = data_dir + 'rgb/' mask_dir = data_dir + 'mask/' gt_dir = data_dir + 'gt/' rgb_addrs = glob.glob(rgb_dir + '*.png') global_accuracy = 0 accur_dir = data_dir + 'mask/accuracy.txt' accur_file = open(accur_dir, 'w') count = 0 for i in range(len(rgb_addrs)): str_num = rgb_addrs[i][len(rgb_dir):len(rgb_dir)+6] # Read image image = skimage.io.imread(rgb_addrs[i]) # Detect objects r = model.detect([image], verbose=1)[0] # get instance_masks semantic_masks, instance_masks, color_masks = get_masks(image, r['masks'], r['class_ids']) # save mask image mask_addr = data_dir + 'mask/' + rgb_addrs[i][len(rgb_dir):] skimage.io.imsave(mask_addr, color_masks) # evaluation gt_addr = gt_dir + str_num + '-label.png' if os.path.isfile(gt_addr) == False: continue; gt = skimage.io.imread(gt_addr) dif = semantic_masks - gt accuracy = 1 - np.count_nonzero(dif) / (gt.shape[0]*gt.shape[1]) accur_file.write('%s %f\n' % (str_num, accuracy)) global_accuracy = global_accuracy + accuracy count +=1 if count: accur_file.write('Mean accuracy: %f' % (global_accuracy / count)) accur_file.close() if __name__ == '__main__': class InferenceConfig(WarehouseConfig): GPU_COUNT = 1 IMAGES_PER_GPU = 1 config = InferenceConfig() config.display() weights_dir = os.path.abspath("../../../") + '/data/trained_models/warehouse/mask_rcnn.h5' model = modellib.MaskRCNN(mode="inference", config=config, model_dir=weights_dir) model.load_weights(weights_dir, by_name=True) detect_and_get_masks(model) ================================================ FILE: Mask_RCNN/samples/warehouse/iliad.py ================================================ """ Mask R-CNN for Object_RPE ------------------------------------------------------------ """ import os import sys import json import datetime import numpy as np import skimage.draw import glob import matplotlib.pyplot as plt import matplotlib.image as mpimg # Root directory of the project ROOT_DIR = os.path.abspath("../../") # Import Mask RCNN sys.path.append(ROOT_DIR) # To find local version of the library from mrcnn.config import Config from mrcnn import model as modellib, utils # Path to trained weights file DEFAULT_LOGS_DIR = os.path.join(ROOT_DIR, "logs") class WarehouseConfig(Config): """Configuration for training on the toy dataset. Derives from the base Config class and overrides some values. """ # Give the configuration a recognizable name NAME = "Warehouse" # We use a GPU with 12GB memory, which can fit two images. # Adjust down if you use a smaller GPU. IMAGES_PER_GPU = 1 # Number of classes (including background) NUM_CLASSES = 1 + 13 # Background + objects # Number of training steps per epoch STEPS_PER_EPOCH = 400 # Skip detections with < 90% confidence DETECTION_MIN_CONFIDENCE = 0.7 def seq_get_masks(image, cur_detection): cur_masks = cur_detection['masks'] cur_class_ids = cur_detection['class_ids'] cur_rois = cur_detection['rois'] instance_masks = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) semantic_masks = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) semantic_mask_one = np.ones((image.shape[0], image.shape[1]), dtype=np.uint8) instance_mask_one = np.ones((image.shape[0], image.shape[1]), dtype=np.uint8) print('cur_masks.shape: {}'.format(cur_masks.shape[-1])) if cur_masks.shape[-1] > 0: mask_zero = np.zeros((image.shape[0], image.shape[1]), dtype=np.uint8) for i in range(cur_masks.shape[-1]): semantic_mask = semantic_mask_one * cur_class_ids[i] semantic_masks = np.where(cur_masks[:, :, i], semantic_mask, semantic_masks).astype(np.uint8) instance_mask = instance_mask_one * (i+1) instance_masks = np.where(cur_masks[:, :, i], instance_mask, instance_masks).astype(np.uint8) return semantic_masks, instance_masks def detect_and_get_masks(model, data_path, num_frames, num_keyframes): incr = num_frames//num_keyframes if incr < 1: return; for i in range(0, num_frames, incr): num = 1000001 + i str_num = str(num)[1:] rgb_addr = "rgb/" + str_num + "-color.png" rgb_addr = os.path.join(data_path, rgb_addr) depth_addr = "depth/" + str_num + "-depth.png" depth_addr = os.path.join(data_path, depth_addr) if os.path.isfile(rgb_addr) == False: continue; if os.path.isfile(depth_addr) == False: continue; # Read image image = skimage.io.imread(rgb_addr) depth = skimage.io.imread(depth_addr) # Detect objects cur_detect = model.detect([image], verbose=1)[0] file_name = 'mask/' + str_num + '-class_ids.txt' file_dir = os.path.join(data_path, file_name) with open(file_dir, 'w') as the_file: for j in range (cur_detect['class_ids'].shape[0]): the_file.write(str(cur_detect['class_ids'][j])) the_file.write('\n') # get instance_masks semantic_masks, instance_masks = seq_get_masks(image, cur_detect) file_name = 'mask/' + str_num + '-mask.png' mask_addr = os.path.join(data_path, file_name) skimage.io.imsave(mask_addr, instance_masks) plt.subplot(2, 2, 1) plt.title('rgb') plt.imshow(image) plt.subplot(2, 2, 2) plt.title('depth') plt.imshow(depth) plt.subplot(2, 2, 3) plt.title('mask') plt.imshow(instance_masks) plt.subplot(2, 2, 4) plt.title('label') plt.imshow(semantic_masks) plt.draw() plt.pause(0.001) #plt.show() if __name__ == '__main__': import argparse # Parse command line arguments parser = argparse.ArgumentParser( description='Train Mask R-CNN to detect Warehouses.') parser.add_argument('--data', required=False, metavar="/path/to/data/", help='Directory of the Warehouse dataset') parser.add_argument('--weights', required=True, metavar="/path/to/weights.h5", help="Path to weights .h5 file or 'coco'") parser.add_argument('--logs', required=False, default=DEFAULT_LOGS_DIR, metavar="/path/to/logs/", help='Logs and checkpoints directory (default=logs/)') parser.add_argument('--num_frames', type=int, default = 100, help='number of images') parser.add_argument('--num_keyframes', type=int, default = 10, help='real number of images applied') args = parser.parse_args() class InferenceConfig(WarehouseConfig): GPU_COUNT = 1 IMAGES_PER_GPU = 1 config = InferenceConfig() config.display() model = modellib.MaskRCNN(mode="inference", config=config, model_dir=args.logs) weights_path = args.weights model.load_weights(weights_path, by_name=True) detect_and_get_masks(model, args.data, args.num_frames, args.num_keyframes) ================================================ FILE: Mask_RCNN/samples/warehouse/note.txt ================================================ # To train python3 train.py --dataset=/Warehouse_Dataset/data --weights=coco python3 train.py --dataset=/Warehouse_Dataset/data --weights=last # To evaluate python3 eval.py It will read rgb and ground-truth images from /rgb and gt/ folders in .../Object-RPE/data then save results in .../Object-RPE/data/mask ================================================ FILE: Mask_RCNN/samples/warehouse/train.py ================================================ """ Mask R-CNN Train on the Warehouse dataset and implement color splash effect. Based on the work of Waleed Abdulla (Matterport) Modified by Dinh-Cuong Hoang ------------------------------------------------------------ python3 train.py --dataset=/Warehouse_Dataset/data --weights=coco python3 train.py --dataset=/Warehouse_Dataset/data --weights=last """ import os import sys import json import datetime import numpy as np import skimage.draw import matplotlib.pyplot as plt import matplotlib.image as mpimg # Root directory of the project ROOT_DIR = os.path.abspath("../../") # Import Mask RCNN sys.path.append(ROOT_DIR) # To find local version of the library from mrcnn.config import Config from mrcnn import model as modellib, utils # Path to trained weights file COCO_WEIGHTS_PATH = os.path.join(ROOT_DIR, "mask_rcnn_coco.h5") # Directory to save logs and model checkpoints, if not provided # through the command line argument --logs DEFAULT_LOGS_DIR = os.path.join(ROOT_DIR, "logs") ############################################################ # Configurations ############################################################ class WarehouseConfig(Config): """Configuration for training on the toy dataset. Derives from the base Config class and overrides some values. """ # Give the configuration a recognizable name NAME = "Warehouse" # We use a GPU with 12GB memory, which can fit two images. # Adjust down if you use a smaller GPU. IMAGES_PER_GPU = 1 # Number of classes (including background) NUM_CLASSES = 1 + 13 # Background + objects # Number of training steps per epoch STEPS_PER_EPOCH = 400 # Skip detections with < 90% confidence DETECTION_MIN_CONFIDENCE = 0.9 ############################################################ # Dataset ############################################################ class WarehouseDataset(utils.Dataset): def load_Warehouse(self, dataset_dir, subset): """Load a subset of the Warehouse dataset. dataset_dir: Root directory of the dataset. subset: Subset to load: train or val """ # Add classes. We have only one class to add. self.add_class("Warehouse", 1, "pallet_free") self.add_class("Warehouse", 2, "half_pallet_free") self.add_class("Warehouse", 3, "pallet_occluded") self.add_class("Warehouse", 4, "half_pallet_occluded") self.add_class("Warehouse", 5, "jacky") self.add_class("Warehouse", 6, "frasvaf") self.add_class("Warehouse", 7, "onos") self.add_class("Warehouse", 8, "pauluns") self.add_class("Warehouse", 9, "risi_frutti") self.add_class("Warehouse", 10, "skansk") self.add_class("Warehouse", 11, "sotstark") self.add_class("Warehouse", 12, "tomatpure") self.add_class("Warehouse", 13, "small_jacky") # Train or validation dataset? assert subset in ["train", "val"] dataset_path = os.path.join(dataset_dir, 'via_region_data_train.json') dataset_path = os.path.join(dataset_dir, 'via_region_data_val.json') annotations = json.load(open(dataset_path)) annotations = list(annotations.values()) # don't need the dict keys # The VIA tool saves images in the JSON even if they don't have any # annotations. Skip unannotated images. annotations = [a for a in annotations if a['regions']] # Add images for a in annotations: # Get the x, y coordinaets of points of the polygons that make up # the outline of each object instance. These are stores in the # shape_attributes (see json format above) # The if condition is needed to support VIA versions 1.x and 2.x. if type(a['regions']) is dict: polygons = [r['shape_attributes'] for r in a['regions'].values()] else: polygons = [r['shape_attributes'] for r in a['regions']] # the image. This is only managable since the dataset is tiny. image_path = os.path.join(dataset_dir, a['filename']) image = skimage.io.imread(image_path) height, width = image.shape[:2] self.add_image( "Warehouse", image_id=a['filename'], # use file name as a unique image id path=image_path, width=width, height=height, polygons=polygons) def load_mask(self, image_id): """Generate instance masks for an image. Returns: masks: A bool array of shape [height, width, instance count] with one mask per instance. class_ids: a 1D array of class IDs of the instance masks. """ # If not a Warehouse dataset image, delegate to parent class. image_info = self.image_info[image_id] if image_info["source"] != "Warehouse": return super(self.__class__, self).load_mask(image_id) # Convert polygons to a bitmap mask of shape # [height, width, instance_count] info = self.image_info[image_id] mask = np.zeros([info["height"], info["width"], len(info["polygons"])], dtype=np.uint8) class_IDs = np.zeros([len(info["polygons"])], dtype=np.int32) for i, p in enumerate(info["polygons"]): # Get indexes of pixels inside the polygon and set them to 1 rr, cc = skimage.draw.polygon(p['all_points_y'], p['all_points_x']) mask[rr, cc, i] = 1 class_IDs[i] = p['class_id'] # Return mask, and array of class IDs of each instance. Since we have # one class ID only, we return an array of 1s return mask.astype(np.bool), class_IDs def image_reference(self, image_id): """Return the path of the image.""" info = self.image_info[image_id] if info["source"] == "Warehouse": return info["path"] else: super(self.__class__, self).image_reference(image_id) def train(model): """Train the model.""" # Training dataset. dataset_train = WarehouseDataset() dataset_train.load_Warehouse(args.dataset, "train") dataset_train.prepare() # Validation dataset dataset_val = WarehouseDataset() dataset_val.load_Warehouse(args.dataset, "val") dataset_val.prepare() # *** This training schedule is an example. Update to your needs *** # Since we're using a very small dataset, and starting from # COCO trained weights, we don't need to train too long. Also, # no need to train all layers, just the heads should do it. # Training - Stage 1 print("Training network heads") model.train(dataset_train, dataset_val, learning_rate=config.LEARNING_RATE, epochs=100, layers='heads') #Training - Stage 2 #Finetune layers from ResNet stage 4 and up ''' print("Fine tune Resnet stage 4 and up") model.train(dataset_train, dataset_val, learning_rate=config.LEARNING_RATE, epochs=60, layers='4+') ''' # Training - Stage 3 # Fine tune all layers ''' print("Fine tune all layers") model.train(dataset_train, dataset_val, learning_rate=config.LEARNING_RATE / 10, epochs=80, layers='all') ''' ############################################################ # Training ############################################################ if __name__ == '__main__': import argparse # Parse command line arguments parser = argparse.ArgumentParser( description='Train Mask R-CNN to detect Warehouses.') parser.add_argument('--dataset', required=False, metavar="/path/to/Warehouse/dataset/", help='Directory of the Warehouse dataset') parser.add_argument('--weights', required=True, metavar="/path/to/weights.h5", help="Path to weights .h5 file or 'coco'") parser.add_argument('--logs', required=False, default=DEFAULT_LOGS_DIR, metavar="/path/to/logs/", help='Logs and checkpoints directory (default=logs/)') args = parser.parse_args() # Validate arguments assert args.dataset, "Argument --dataset is required for training" print("Weights: ", args.weights) print("Dataset: ", args.dataset) print("Logs: ", args.logs) # Configurations config = WarehouseConfig() # Create model model = modellib.MaskRCNN(mode="training", config=config, model_dir=args.logs) # Select weights file to load if args.weights.lower() == "coco": weights_path = COCO_WEIGHTS_PATH # Download weights file if not os.path.exists(weights_path): utils.download_trained_weights(weights_path) elif args.weights.lower() == "last": # Find last trained weights weights_path = model.find_last() elif args.weights.lower() == "imagenet": # Start from ImageNet trained weights weights_path = model.get_imagenet_weights() else: weights_path = args.weights # Load weights print("Loading weights ", weights_path) if args.weights.lower() == "coco": # Exclude the last layers because they require a matching # number of classes model.load_weights(weights_path, by_name=True, exclude=[ "mrcnn_class_logits", "mrcnn_bbox_fc", "mrcnn_bbox", "mrcnn_mask"]) else: model.load_weights(weights_path, by_name=True) # Train or evaluate train(model) ================================================ FILE: Mask_RCNN/setup.cfg ================================================ [metadata] description-file = README.md license-file = LICENSE requirements-file = requirements.txt ================================================ FILE: Mask_RCNN/setup.py ================================================ """ The build/compilations setup >> pip install -r requirements.txt >> python setup.py install """ import pip import logging import pkg_resources try: from setuptools import setup except ImportError: from distutils.core import setup def _parse_requirements(file_path): pip_ver = pkg_resources.get_distribution('pip').version pip_version = list(map(int, pip_ver.split('.')[:2])) if pip_version >= [6, 0]: raw = pip.req.parse_requirements(file_path, session=pip.download.PipSession()) else: raw = pip.req.parse_requirements(file_path) return [str(i.req) for i in raw] # parse_requirements() returns generator of pip.req.InstallRequirement objects try: install_reqs = _parse_requirements("requirements.txt") except Exception: logging.warning('Fail load requirements file, so using default ones.') install_reqs = [] setup( name='mask-rcnn', version='2.1', url='https://github.com/matterport/Mask_RCNN', author='Matterport', author_email='waleed.abdulla@gmail.com', license='MIT', description='Mask R-CNN for object detection and instance segmentation', packages=["mrcnn"], install_requires=install_reqs, include_package_data=True, python_requires='>=3.4', long_description="""This is an implementation of Mask R-CNN on Python 3, Keras, and TensorFlow. The model generates bounding boxes and segmentation masks for each instance of an object in the image. It's based on Feature Pyramid Network (FPN) and a ResNet101 backbone.""", classifiers=[ "Development Status :: 5 - Production/Stable", "Environment :: Console", "Intended Audience :: Developers", "Intended Audience :: Information Technology", "Intended Audience :: Education", "Intended Audience :: Science/Research", "License :: OSI Approved :: MIT License", "Natural Language :: English", "Operating System :: OS Independent", "Topic :: Scientific/Engineering :: Artificial Intelligence", "Topic :: Scientific/Engineering :: Image Recognition", "Topic :: Scientific/Engineering :: Visualization", "Topic :: Scientific/Engineering :: Image Segmentation", 'Programming Language :: Python :: 3.4', 'Programming Language :: Python :: 3.5', 'Programming Language :: Python :: 3.6', ], keywords="image instance segmentation object detection mask rcnn r-cnn tensorflow keras", ) ================================================ FILE: README.md ================================================ # 6D Object Pose Estimation (D6.4 [ILIAD](https://iliad-project.eu)) This contains a brief guide how to install / run the ROS-based simplified [Object-RPE](https://sites.google.com/view/object-rpe) developed at ORU in D6.4 [ILIAD](https://iliad-project.eu) project. ## The set of 11 objects in our warehouse dataset. ![The set of 11 objects](figs/ex1.png) ## Installation and compile the source The tools require full ROS installation. The installation assumes you have Ubuntu 16.04 LTS [ROS Kinetic] 1. Clone the repository and switch to iliad branch ```bash $ https://github.com/hoangcuongbk80/Object-RPE.git $ git checkout iliad ``` 2. ROS ```bash $ cd ~/catkin_ws $ catkin_make install ``` 3. Segmentation [here](https://github.com/hoangcuongbk80/Object-RPE/tree/iliad/Mask_RCNN) 4. 3D mapping [here](https://github.com/hoangcuongbk80/Object-RPE/tree/iliad/obj_pose_est/mapping) 5. 6D object pose estimation [here](https://github.com/hoangcuongbk80/Object-RPE/tree/iliad/DenseFusion) ## Testing 1. Download data folder [here](https://drive.google.com/file/d/1dzwcLOiakkSLiUoJXkPD8-QkIBFTJMXQ/view?usp=sharing) and copy to ~/catkin_ws/src/Object-RPE 2. To test segmenation module: ```bash $ cd ~/catkin_ws/src/Object_RPE/Mask-RCNN/samples/warehouse $ python3 eval.py ``` It will read rgb and ground-truth images from /rgb and gt/ folders in .../Object-RPE/data then save results (mask and accuracy.txt file) into .../Object-RPE/data/mask 3. To test 3D mapping module: ```bash $ cd ~/catkin_ws/src/Object-RPE/obj_pose_est/mapping/app $ ./obj_pose_est/mapping/app/build/mapping -l data/ 100 ``` 4. To test pose estimation module ([Video](https://www.youtube.com/watch?v=1CSoOjFgP-I)): ```bash $ roscore ``` In an other terminal: ```bash $ rosrun obj_pose_est ObjectRPE_srv.py ``` In an other terminal: ```bash $ roslaunch obj_pose_est launch_object_rpe.launch ``` ## How to operate the system? ```bash $ roscore $ rosrun obj_pose_est ObjectRPE_srv.py $ roslaunch obj_pose_est launch_rpe_cam.launch $ roslaunch openni2_launch openni2.launch ``` ================================================ FILE: obj_pose_est/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.8.3) project(obj_pose_est) ## Compile as C++11, supported in ROS Kinetic and newer add_compile_options(-std=c++11) ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(OpenCV 3 REQUIRED COMPONENTS opencv_core opencv_imgproc opencv_imgcodecs opencv_highgui opencv_calib3d CONFIG ) find_package(Boost REQUIRED COMPONENTS system) find_package(catkin REQUIRED COMPONENTS cv_bridge pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs std_srvs visualization_msgs message_generation ) find_package(PCL REQUIRED) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html # catkin_python_setup() ################################################ ## Declare ROS messages, services and actions ## ################################################ ## To declare and build messages, services or actions from within this ## package, follow these steps: ## * Let MSG_DEP_SET be the set of packages whose message types you use in ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). ## * In the file package.xml: ## * add a build_depend tag for "message_generation" ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in ## but can be declared for certainty nonetheless: ## * add a exec_depend tag for "message_runtime" ## * In this file (CMakeLists.txt): ## * add "message_generation" and every package in MSG_DEP_SET to ## find_package(catkin REQUIRED COMPONENTS ...) ## * add "message_runtime" and every package in MSG_DEP_SET to ## catkin_package(CATKIN_DEPENDS ...) ## * uncomment the add_*_files sections below as needed ## and list every .msg/.srv/.action file to be processed ## * uncomment the generate_messages entry below ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder # add_message_files( # FILES # Message1.msg # Message2.msg # ) ## Generate services in the 'srv' folder # add_service_files( # FILES # Service1.srv # Service2.srv # ) add_service_files( FILES ObjectRPE.srv ) ## Generate actions in the 'action' folder # add_action_files( # FILES # Action1.action # Action2.action # ) ## Generate added messages and services with any dependencies listed here # generate_messages( # DEPENDENCIES # sensor_msgs# std_msgs# visualization_msgs # ) generate_messages( DEPENDENCIES std_msgs ) ################################################ ## Declare ROS dynamic reconfigure parameters ## ################################################ ## To declare and build dynamic reconfigure parameters within this ## package, follow these steps: ## * In the file package.xml: ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" ## * In this file (CMakeLists.txt): ## * add "dynamic_reconfigure" to ## find_package(catkin REQUIRED COMPONENTS ...) ## * uncomment the "generate_dynamic_reconfigure_options" section below ## and list every .cfg file to be processed ## Generate dynamic reconfigure parameters in the 'cfg' folder # generate_dynamic_reconfigure_options( # cfg/DynReconf1.cfg # cfg/DynReconf2.cfg # ) ################################### ## catkin specific configuration ## ################################### ## The catkin_package macro generates cmake config files for your package ## Declare things to be passed to dependent projects ## INCLUDE_DIRS: uncomment this if your package contains header files ## LIBRARIES: libraries you create in this project that dependent projects also need ## CATKIN_DEPENDS: catkin_packages dependent projects also need ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( INCLUDE_DIRS include LIBRARIES obj_pose_est CATKIN_DEPENDS message_runtime cv_bridge pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs std_srvs visualization_msgs DEPENDS system_lib ) ########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories( include ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} ) ## Declare a C++ library add_library(${PROJECT_NAME} src/model_to_scene.cpp src/kalman_filter.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide # add_executable(${PROJECT_NAME}_node src/obj_pose_est_node.cpp) add_executable(iliad_rpe_node src/iliad_rpe_node.cpp) add_executable(iliad_rpe_cam_node src/iliad_rpe_cam_node.cpp) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") ## Add cmake target dependencies of the executable ## same as for the library above # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against # target_link_libraries(${PROJECT_NAME}_node # ${catkin_LIBRARIES} # ) target_link_libraries(iliad_rpe_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${PROJECT_NAME} ${PCL_LIBRARIES}) target_link_libraries(iliad_rpe_cam_node ${catkin_LIBRARIES} ${OpenCV_LIBS} ${PROJECT_NAME} ${PCL_LIBRARIES}) ############# ## Install ## ############# # all install targets should use catkin DESTINATION variables # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html ## Mark executable scripts (Python etc.) for installation ## in contrast to setup.py, you can choose the destination # install(PROGRAMS # scripts/my_python_script # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark executables and/or libraries for installation # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} # ) ## Mark cpp header files for installation # install(DIRECTORY include/${PROJECT_NAME}/ # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} # FILES_MATCHING PATTERN "*.h" # PATTERN ".svn" EXCLUDE # ) ## Mark other files for installation (e.g. launch and bag files, etc.) # install(FILES # # myfile1 # # myfile2 # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} # ) ############# ## Testing ## ############# ## Add gtest based cpp test target and link libraries # catkin_add_gtest(${PROJECT_NAME}-test test/test_obj_pose_est.cpp) # if(TARGET ${PROJECT_NAME}-test) # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) # endif() ## Add folders to be run by python nosetests # catkin_add_nosetests(test) ================================================ FILE: obj_pose_est/include/obj_pose_est/kalman_filter.h ================================================ #include #include #include #include // PCL #include #include #include #include #include using namespace std; using namespace Eigen; typedef Eigen::Matrix Vector6f; typedef Eigen::Matrix Matrix6f; #ifndef KALMAN_FILTER_H #define KALMAN_FILTER_H class kalman_filter { public: kalman_filter(); virtual ~kalman_filter(); bool Kalman_update(const Vector6f &measure_X, const Matrix6f &measure_cov, Vector6f &est_X, Matrix6f &est_cov); inline Vector6f addPose(const Vector6f &origin, const Vector6f &pose); inline Vector6f subPose(const Vector6f &origin, const Vector6f &pose); }; #endif ================================================ FILE: obj_pose_est/include/obj_pose_est/model_to_scene.h ================================================ #include #include // OpenCV specific includes #include // PCL specific includes #include #include #include #include #include #include #include #include #include #include #include //plane fitting #include #include #include #include #include #include #include #include #include #include #include #include #include #include #ifndef MODEL_TO_SCENE_H #define MODEL_TO_SCENE_H struct boundingBBox { double length[3]; pcl::PointXYZ minPoint, maxPoint; //min max Point after trasferring to origin pcl::PointXYZ center; Eigen::Matrix4f toOrigin; //pcl::transformPointCloud(input, output, toOrigin); pcl::PointCloud cornerPoints; }; struct ObjectModel { std::string name; pcl::PointCloud points_full; pcl::PointCloud points_view; boundingBBox OBB; }; struct ObjectInstance { std::string name; pcl::PointCloud points; boundingBBox OBB; }; class model_to_scene { public: model_to_scene(); virtual ~model_to_scene(); std::vector instances; std::vector models; void computeOBB(const pcl::PointCloud &input, boundingBBox &OBB); void processCloud(const std::string cloud_path, const std::string detected_class_ids_path, const std::string class_list_path, const std::string model_dir); void coarseToFineRegistration(const pcl::PointCloud &sourceCloud, const pcl::PointCloud &modelCloud, const pcl::PointCloud &targetCloud, pcl::PointCloud ®isted_source); void cloud_to_instances(const pcl::PointCloud &input, std::vector &objects); int color_to_instanceID(unsigned char r, unsigned char g, unsigned char b); void noiseRemoval(std::vector &objects); void load_models(const std::string model_dir, const std::string detected_class_ids_path, const std::string class_list_path, std::vector &models); double overlapPortion(const pcl::PointCloud &source, const pcl::PointCloud &target, const double &max_dist); }; #endif ================================================ FILE: obj_pose_est/launch/launch_iliad_cam.launch ================================================ ================================================ FILE: obj_pose_est/launch/launch_iliad_rpe.launch ================================================ ================================================ FILE: obj_pose_est/mapping/Core/src/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.6.0) project(libefusion) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}") find_package(Pangolin 0.1 REQUIRED) find_package(CUDA REQUIRED) find_package(SuiteSparse REQUIRED) find_package(OpenCV 3.1 REQUIRED) set(efusion_SHADER_DIR "${CMAKE_CURRENT_SOURCE_DIR}/Shaders" CACHE PATH "Where the shaders live") include_directories(${Pangolin_INCLUDE_DIRS}) include_directories(${CUDA_INCLUDE_DIRS}) include_directories(${EIGEN_INCLUDE_DIRS}) include_directories(${SUITESPARSE_INCLUDE_DIRS}) include_directories(${OpenCV_INCLUDE_DIRS}) file(GLOB srcs *.cpp) file(GLOB utils_srcs Utils/*.cpp) file(GLOB shader_srcs Shaders/*.cpp) file(GLOB cuda Cuda/*.cu) file(GLOB containers Cuda/containers/*.cpp) if(WIN32) file(GLOB hdrs *.h) file(GLOB utils_hdrs Utils/*.h) file(GLOB shader_hdrs Shaders/*.h) file(GLOB cuda_hdrs Cuda/*.cuh) file(GLOB containers_hdrs Cuda/containers/*.hpp) endif() set(CUDA_ARCH_BIN "30 35 50 52 61" CACHE STRING "Specify 'real' GPU arch to build binaries for, BIN(PTX) format is supported. Example: 1.3 2.1(1.3) or 13 21(13)") set(CUDA_ARCH_PTX "" CACHE STRING "Specify 'virtual' PTX arch to build PTX intermediate code for. Example: 1.0 1.2 or 10 12") SET(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_CURRENT_SOURCE_DIR}) include(CudaComputeTargetFlags.cmake) APPEND_TARGET_ARCH_FLAGS() set(CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS} "-Xcompiler;-fPIC;") set(CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS} "--ftz=true;--prec-div=false;--prec-sqrt=false") CUDA_COMPILE(cuda_objs ${cuda}) if(WIN32) set(ADDITIONAL_CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS}) endif() set(CMAKE_CXX_FLAGS ${ADDITIONAL_CMAKE_CXX_FLAGS} "-O3 -msse2 -msse3 -Wall -std=c++11 -DSHADER_DIR=${efusion_SHADER_DIR}") #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -Wall -std=c++11 -DSHADER_DIR=${efusion_SHADER_DIR}") if(WIN32) add_definitions(-DWIN32_LEAN_AND_MEAN) add_definitions(-DNOMINMAX) set (EXTRA_WINDOWS_LIBS ${EXTRA_WINDOWS_LIBS} ws2_32) endif() add_library(efusion SHARED ${srcs} ${utils_srcs} ${shader_srcs} ${cuda} ${cuda_objs} ${containers} ${hdrs} ${utils_hdrs} ${shader_hdrs} ${cuda_hdrs} ${containers_hdrs} ) target_link_libraries(efusion ${Eigen_LIBRARIES} ${Pangolin_LIBRARIES} ${CUDA_LIBRARIES} ${SUITESPARSE_LIBRARIES} ${OpenCV_LIBRARIES} ${EXTRA_WINDOWS_LIBS} ) INSTALL(TARGETS efusion RUNTIME DESTINATION bin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib ) ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/device_array.hpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef DEVICE_ARRAY_HPP_ #define DEVICE_ARRAY_HPP_ #include "device_memory.hpp" #include ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief @b DeviceArray class * * \note Typed container for GPU memory with reference counting. * * \author Anatoly Baksheev */ template class DeviceArray : public DeviceMemory { public: /** \brief Element type. */ typedef T type; /** \brief Element size. */ enum { elem_size = sizeof(T) }; /** \brief Empty constructor. */ DeviceArray(); /** \brief Allocates internal buffer in GPU memory * \param size_t: number of elements to allocate * */ DeviceArray(size_t size); /** \brief Initializes with user allocated buffer. Reference counting is disabled in this case. * \param ptr: pointer to buffer * \param size: elemens number * */ DeviceArray(T *ptr, size_t size); /** \brief Copy constructor. Just increments reference counter. */ DeviceArray(const DeviceArray& other); /** \brief Assigment operator. Just increments reference counter. */ DeviceArray& operator = (const DeviceArray& other); /** \brief Allocates internal buffer in GPU memory. If internal buffer was created before the function recreates it with new size. If new and old sizes are equal it does nothing. * \param size: elemens number * */ void create(size_t size); /** \brief Decrements reference counter and releases internal buffer if needed. */ void release(); /** \brief Performs data copying. If destination size differs it will be reallocated. * \param other_arg: destination container * */ void copyTo(DeviceArray& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param host_ptr_arg: pointer to buffer to upload * \param size: elemens number * */ void upload(const T *host_ptr, size_t size); /** \brief Downloads data from internal buffer to CPU memory * \param host_ptr_arg: pointer to buffer to download * */ void download(T *host_ptr) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param data: host vector to upload from * */ template void upload(const std::vector& data); /** \brief Downloads data from internal buffer to CPU memory * \param data: host vector to download to * */ template void download(std::vector& data) const; /** \brief Performs swap of data pointed with another device array. * \param other: device array to swap with * */ void swap(DeviceArray& other_arg); /** \brief Returns pointer for internal buffer in GPU memory. */ T* ptr(); /** \brief Returns const pointer for internal buffer in GPU memory. */ const T* ptr() const; //using DeviceMemory::ptr; /** \brief Returns pointer for internal buffer in GPU memory. */ operator T*(); /** \brief Returns const pointer for internal buffer in GPU memory. */ operator const T*() const; /** \brief Returns size in elements. */ size_t size() const; }; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief @b DeviceArray2D class * * \note Typed container for pitched GPU memory with reference counting. * * \author Anatoly Baksheev */ template class DeviceArray2D : public DeviceMemory2D { public: /** \brief Element type. */ typedef T type; /** \brief Element size. */ enum { elem_size = sizeof(T) }; /** \brief Empty constructor. */ DeviceArray2D(); /** \brief Allocates internal buffer in GPU memory * \param rows: number of rows to allocate * \param cols: number of elements in each row * */ DeviceArray2D(int rows, int cols); /** \brief Initializes with user allocated buffer. Reference counting is disabled in this case. * \param rows: number of rows * \param cols: number of elements in each row * \param data: pointer to buffer * \param stepBytes: stride between two consecutive rows in bytes * */ DeviceArray2D(int rows, int cols, void *data, size_t stepBytes); /** \brief Copy constructor. Just increments reference counter. */ DeviceArray2D(const DeviceArray2D& other); /** \brief Assigment operator. Just increments reference counter. */ DeviceArray2D& operator = (const DeviceArray2D& other); /** \brief Allocates internal buffer in GPU memory. If internal buffer was created before the function recreates it with new size. If new and old sizes are equal it does nothing. * \param rows: number of rows to allocate * \param cols: number of elements in each row * */ void create(int rows, int cols); /** \brief Decrements reference counter and releases internal buffer if needed. */ void release(); /** \brief Performs data copying. If destination size differs it will be reallocated. * \param other: destination container * */ void copyTo(DeviceArray2D& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param host_ptr: pointer to host buffer to upload * \param host_step: stride between two consecutive rows in bytes for host buffer * \param rows: number of rows to upload * \param cols: number of elements in each row * */ void upload(const void *host_ptr, size_t host_step, int rows, int cols); /** \brief Downloads data from internal buffer to CPU memory. User is resposible for correct host buffer size. * \param host_ptr: pointer to host buffer to download * \param host_step: stride between two consecutive rows in bytes for host buffer * */ void download(void *host_ptr, size_t host_step) const; /** \brief Performs swap of data pointed with another device array. * \param other: device array to swap with * */ void swap(DeviceArray2D& other_arg); /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param data: host vector to upload from * \param cols: stride in elements between two consecutive rows in bytes for host buffer * */ template void upload(const std::vector& data, int cols); /** \brief Downloads data from internal buffer to CPU memory * \param data: host vector to download to * \param cols: Output stride in elements between two consecutive rows in bytes for host vector. * */ template void download(std::vector& data, int& cols) const; /** \brief Returns pointer to given row in internal buffer. * \param y_arg: row index * */ T* ptr(int y = 0); /** \brief Returns const pointer to given row in internal buffer. * \param y_arg: row index * */ const T* ptr(int y = 0) const; //using DeviceMemory2D::ptr; /** \brief Returns pointer for internal buffer in GPU memory. */ operator T*(); /** \brief Returns const pointer for internal buffer in GPU memory. */ operator const T*() const; /** \brief Returns number of elements in each row. */ int cols() const; /** \brief Returns number of rows. */ int rows() const; /** \brief Returns step in elements. */ size_t elem_step() const; }; #include "device_array_impl.hpp" #endif /* DEVICE_ARRAY_HPP_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/device_array_impl.hpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef DEVICE_ARRAY_IMPL_HPP_ #define DEVICE_ARRAY_IMPL_HPP_ ///////////////////// Inline implementations of DeviceArray //////////////////////////////////////////// template inline DeviceArray::DeviceArray() {} template inline DeviceArray::DeviceArray(size_t size) : DeviceMemory(size * elem_size) {} template inline DeviceArray::DeviceArray(T *ptr, size_t size) : DeviceMemory(ptr, size * elem_size) {} template inline DeviceArray::DeviceArray(const DeviceArray& other) : DeviceMemory(other) {} template inline DeviceArray& DeviceArray::operator=(const DeviceArray& other) { DeviceMemory::operator=(other); return *this; } template inline void DeviceArray::create(size_t size) { DeviceMemory::create(size * elem_size); } template inline void DeviceArray::release() { DeviceMemory::release(); } template inline void DeviceArray::copyTo(DeviceArray& other) const { DeviceMemory::copyTo(other); } template inline void DeviceArray::upload(const T *host_ptr, size_t size) { DeviceMemory::upload(host_ptr, size * elem_size); } template inline void DeviceArray::download(T *host_ptr) const { DeviceMemory::download( host_ptr ); } template void DeviceArray::swap(DeviceArray& other_arg) { DeviceMemory::swap(other_arg); } template inline DeviceArray::operator T*() { return ptr(); } template inline DeviceArray::operator const T*() const { return ptr(); } template inline size_t DeviceArray::size() const { return sizeBytes() / elem_size; } template inline T* DeviceArray::ptr() { return DeviceMemory::ptr(); } template inline const T* DeviceArray::ptr() const { return DeviceMemory::ptr(); } template template inline void DeviceArray::upload(const std::vector& data) { upload(&data[0], data.size()); } template template inline void DeviceArray::download(std::vector& data) const { data.resize(size()); if (!data.empty()) download(&data[0]); } ///////////////////// Inline implementations of DeviceArray2D //////////////////////////////////////////// template inline DeviceArray2D::DeviceArray2D() {} template inline DeviceArray2D::DeviceArray2D(int rows, int cols) : DeviceMemory2D(rows, cols * elem_size) {} template inline DeviceArray2D::DeviceArray2D(int rows, int cols, void *data, size_t stepBytes) : DeviceMemory2D(rows, cols * elem_size, data, stepBytes) {} template inline DeviceArray2D::DeviceArray2D(const DeviceArray2D& other) : DeviceMemory2D(other) {} template inline DeviceArray2D& DeviceArray2D::operator=(const DeviceArray2D& other) { DeviceMemory2D::operator=(other); return *this; } template inline void DeviceArray2D::create(int rows, int cols) { DeviceMemory2D::create(rows, cols * elem_size); } template inline void DeviceArray2D::release() { DeviceMemory2D::release(); } template inline void DeviceArray2D::copyTo(DeviceArray2D& other) const { DeviceMemory2D::copyTo(other); } template inline void DeviceArray2D::upload(const void *host_ptr, size_t host_step, int rows, int cols) { DeviceMemory2D::upload(host_ptr, host_step, rows, cols * elem_size); } template inline void DeviceArray2D::download(void *host_ptr, size_t host_step) const { DeviceMemory2D::download( host_ptr, host_step ); } template template inline void DeviceArray2D::upload(const std::vector& data, int cols) { upload(&data[0], cols * elem_size, data.size()/cols, cols); } template template inline void DeviceArray2D::download(std::vector& data, int& elem_step) const { elem_step = cols(); data.resize(cols() * rows()); if (!data.empty()) download(&data[0], colsBytes()); } template void DeviceArray2D::swap(DeviceArray2D& other_arg) { DeviceMemory2D::swap(other_arg); } template inline T* DeviceArray2D::ptr(int y) { return DeviceMemory2D::ptr(y); } template inline const T* DeviceArray2D::ptr(int y) const { return DeviceMemory2D::ptr(y); } template inline DeviceArray2D::operator T*() { return ptr(); } template inline DeviceArray2D::operator const T*() const { return ptr(); } template inline int DeviceArray2D::cols() const { return DeviceMemory2D::colsBytes()/elem_size; } template inline int DeviceArray2D::rows() const { return DeviceMemory2D::rows(); } template inline size_t DeviceArray2D::elem_step() const { return DeviceMemory2D::step()/elem_size; } #endif /* DEVICE_ARRAY_IMPL_HPP_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/device_memory.cpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #include "device_memory.hpp" #include "../convenience.cuh" #include "cuda_runtime_api.h" #include "assert.h" ////////////////////////// XADD /////////////////////////////// #ifdef __GNUC__ #if __GNUC__*10 + __GNUC_MINOR__ >= 42 #if !defined WIN32 && (defined __i486__ || defined __i586__ || defined __i686__ || defined __MMX__ || defined __SSE__ || defined __ppc__) #define CV_XADD __sync_fetch_and_add #else #include #define CV_XADD __gnu_cxx::__exchange_and_add #endif #else #include #if __GNUC__*10 + __GNUC_MINOR__ >= 34 #define CV_XADD __gnu_cxx::__exchange_and_add #else #define CV_XADD __exchange_and_add #endif #endif #elif defined WIN32 || defined _WIN32 #include #define CV_XADD(addr,delta) _InterlockedExchangeAdd((long volatile*)(addr), (delta)) #else template static inline _Tp CV_XADD(_Tp* addr, _Tp delta) { int tmp = *addr; *addr += delta; return tmp; } #endif //////////////////////// DeviceArray ///////////////////////////// DeviceMemory::DeviceMemory() : data_(0), sizeBytes_(0), refcount_(0) {} DeviceMemory::DeviceMemory(void *ptr_arg, size_t sizeBytes_arg) : data_(ptr_arg), sizeBytes_(sizeBytes_arg), refcount_(0){} DeviceMemory::DeviceMemory(size_t sizeBtes_arg) : data_(0), sizeBytes_(0), refcount_(0) { create(sizeBtes_arg); } DeviceMemory::~DeviceMemory() { release(); } DeviceMemory::DeviceMemory(const DeviceMemory& other_arg) : data_(other_arg.data_), sizeBytes_(other_arg.sizeBytes_), refcount_(other_arg.refcount_) { if( refcount_ ) CV_XADD(refcount_, 1); } DeviceMemory& DeviceMemory::operator = (const DeviceMemory& other_arg) { if( this != &other_arg ) { if( other_arg.refcount_ ) CV_XADD(other_arg.refcount_, 1); release(); data_ = other_arg.data_; sizeBytes_ = other_arg.sizeBytes_; refcount_ = other_arg.refcount_; } return *this; } void DeviceMemory::create(size_t sizeBytes_arg) { if (sizeBytes_arg == sizeBytes_) return; if( sizeBytes_arg > 0) { if( data_ ) release(); sizeBytes_ = sizeBytes_arg; cudaSafeCall( cudaMalloc(&data_, sizeBytes_) ); refcount_ = new int; *refcount_ = 1; } } void DeviceMemory::copyTo(DeviceMemory& other) const { if (empty()) other.release(); else { other.create(sizeBytes_); cudaSafeCall( cudaMemcpy(other.data_, data_, sizeBytes_, cudaMemcpyDeviceToDevice) ); cudaSafeCall( cudaDeviceSynchronize() ); } } void DeviceMemory::release() { if( refcount_ && CV_XADD(refcount_, -1) == 1 ) { delete refcount_; cudaSafeCall( cudaFree(data_) ); } data_ = 0; sizeBytes_ = 0; refcount_ = 0; } void DeviceMemory::upload(const void *host_ptr_arg, size_t sizeBytes_arg) { create(sizeBytes_arg); cudaSafeCall( cudaMemcpy(data_, host_ptr_arg, sizeBytes_, cudaMemcpyHostToDevice) ); cudaSafeCall( cudaDeviceSynchronize() ); } void DeviceMemory::download(void *host_ptr_arg) const { cudaSafeCall( cudaMemcpy(host_ptr_arg, data_, sizeBytes_, cudaMemcpyDeviceToHost) ); cudaSafeCall( cudaDeviceSynchronize() ); } void DeviceMemory::swap(DeviceMemory& other_arg) { std::swap(data_, other_arg.data_); std::swap(sizeBytes_, other_arg.sizeBytes_); std::swap(refcount_, other_arg.refcount_); } bool DeviceMemory::empty() const { return !data_; } size_t DeviceMemory::sizeBytes() const { return sizeBytes_; } //////////////////////// DeviceArray2D ///////////////////////////// DeviceMemory2D::DeviceMemory2D() : data_(0), step_(0), colsBytes_(0), rows_(0), refcount_(0) {} DeviceMemory2D::DeviceMemory2D(int rows_arg, int colsBytes_arg) : data_(0), step_(0), colsBytes_(0), rows_(0), refcount_(0) { create(rows_arg, colsBytes_arg); } DeviceMemory2D::DeviceMemory2D(int rows_arg, int colsBytes_arg, void *data_arg, size_t step_arg) : data_(data_arg), step_(step_arg), colsBytes_(colsBytes_arg), rows_(rows_arg), refcount_(0) {} DeviceMemory2D::~DeviceMemory2D() { release(); } DeviceMemory2D::DeviceMemory2D(const DeviceMemory2D& other_arg) : data_(other_arg.data_), step_(other_arg.step_), colsBytes_(other_arg.colsBytes_), rows_(other_arg.rows_), refcount_(other_arg.refcount_) { if( refcount_ ) CV_XADD(refcount_, 1); } DeviceMemory2D& DeviceMemory2D::operator = (const DeviceMemory2D& other_arg) { if( this != &other_arg ) { if( other_arg.refcount_ ) CV_XADD(other_arg.refcount_, 1); release(); colsBytes_ = other_arg.colsBytes_; rows_ = other_arg.rows_; data_ = other_arg.data_; step_ = other_arg.step_; refcount_ = other_arg.refcount_; } return *this; } void DeviceMemory2D::create(int rows_arg, int colsBytes_arg) { if (colsBytes_ == colsBytes_arg && rows_ == rows_arg) return; if( rows_arg > 0 && colsBytes_arg > 0) { if( data_ ) release(); colsBytes_ = colsBytes_arg; rows_ = rows_arg; cudaSafeCall( cudaMallocPitch( (void**)&data_, &step_, colsBytes_, rows_) ); refcount_ = new int; *refcount_ = 1; } } void DeviceMemory2D::release() { if( refcount_ && CV_XADD(refcount_, -1) == 1 ) { delete refcount_; cudaSafeCall( cudaFree(data_) ); } colsBytes_ = 0; rows_ = 0; data_ = 0; step_ = 0; refcount_ = 0; } void DeviceMemory2D::copyTo(DeviceMemory2D& other) const { if (empty()) other.release(); else { other.create(rows_, colsBytes_); cudaSafeCall( cudaMemcpy2D(other.data_, other.step_, data_, step_, colsBytes_, rows_, cudaMemcpyDeviceToDevice) ); cudaSafeCall( cudaDeviceSynchronize() ); } } void DeviceMemory2D::upload(const void *host_ptr_arg, size_t host_step_arg, int rows_arg, int colsBytes_arg) { create(rows_arg, colsBytes_arg); cudaSafeCall( cudaMemcpy2D(data_, step_, host_ptr_arg, host_step_arg, colsBytes_, rows_, cudaMemcpyHostToDevice) ); } void DeviceMemory2D::download(void *host_ptr_arg, size_t host_step_arg) const { cudaSafeCall( cudaMemcpy2D(host_ptr_arg, host_step_arg, data_, step_, colsBytes_, rows_, cudaMemcpyDeviceToHost) ); } void DeviceMemory2D::swap(DeviceMemory2D& other_arg) { std::swap(data_, other_arg.data_); std::swap(step_, other_arg.step_); std::swap(colsBytes_, other_arg.colsBytes_); std::swap(rows_, other_arg.rows_); std::swap(refcount_, other_arg.refcount_); } bool DeviceMemory2D::empty() const { return !data_; } int DeviceMemory2D::colsBytes() const { return colsBytes_; } int DeviceMemory2D::rows() const { return rows_; } size_t DeviceMemory2D::step() const { return step_; } ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/device_memory.hpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef DEVICE_MEMORY_HPP_ #define DEVICE_MEMORY_HPP_ #include "kernel_containers.hpp" ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief @b DeviceMemory class * * \note This is a BLOB container class with reference counting for GPU memory. * * \author Anatoly Baksheev */ class DeviceMemory { public: /** \brief Empty constructor. */ DeviceMemory(); /** \brief Destructor. */ ~DeviceMemory(); /** \brief Allocates internal buffer in GPU memory * \param sizeBytes_arg: amount of memory to allocate * */ DeviceMemory(size_t sizeBytes_arg); /** \brief Initializes with user allocated buffer. Reference counting is disabled in this case. * \param ptr_arg: pointer to buffer * \param sizeBytes_arg: buffer size * */ DeviceMemory(void *ptr_arg, size_t sizeBytes_arg); /** \brief Copy constructor. Just increments reference counter. */ DeviceMemory(const DeviceMemory& other_arg); /** \brief Assigment operator. Just increments reference counter. */ DeviceMemory& operator=(const DeviceMemory& other_arg); /** \brief Allocates internal buffer in GPU memory. If internal buffer was created before the function recreates it with new size. If new and old sizes are equal it does nothing. * \param sizeBytes_arg: buffer size * */ void create(size_t sizeBytes_arg); /** \brief Decrements reference counter and releases internal buffer if needed. */ void release(); /** \brief Performs data copying. If destination size differs it will be reallocated. * \param other_arg: destination container * */ void copyTo(DeviceMemory& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param host_ptr_arg: pointer to buffer to upload * \param sizeBytes_arg: buffer size * */ void upload(const void *host_ptr_arg, size_t sizeBytes_arg); /** \brief Downloads data from internal buffer to CPU memory * \param host_ptr_arg: pointer to buffer to download * */ void download(void *host_ptr_arg) const; /** \brief Performs swap of data pointed with another device memory. * \param other: device memory to swap with * */ void swap(DeviceMemory& other_arg); /** \brief Returns pointer for internal buffer in GPU memory. */ template T* ptr(); /** \brief Returns constant pointer for internal buffer in GPU memory. */ template const T* ptr() const; /** \brief Conversion to PtrSz for passing to kernel functions. */ template operator PtrSz() const; /** \brief Returns true if unallocated otherwise false. */ bool empty() const; size_t sizeBytes() const; private: /** \brief Device pointer. */ void *data_; /** \brief Allocated size in bytes. */ size_t sizeBytes_; /** \brief Pointer to reference counter in CPU memory. */ int* refcount_; }; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief @b DeviceMemory2D class * * \note This is a BLOB container class with reference counting for pitched GPU memory. * * \author Anatoly Baksheev */ class DeviceMemory2D { public: /** \brief Empty constructor. */ DeviceMemory2D(); /** \brief Destructor. */ ~DeviceMemory2D(); /** \brief Allocates internal buffer in GPU memory * \param rows_arg: number of rows to allocate * \param colsBytes_arg: width of the buffer in bytes * */ DeviceMemory2D(int rows_arg, int colsBytes_arg); /** \brief Initializes with user allocated buffer. Reference counting is disabled in this case. * \param rows_arg: number of rows * \param colsBytes_arg: width of the buffer in bytes * \param data_arg: pointer to buffer * \param stepBytes_arg: stride between two consecutive rows in bytes * */ DeviceMemory2D(int rows_arg, int colsBytes_arg, void *data_arg, size_t step_arg); /** \brief Copy constructor. Just increments reference counter. */ DeviceMemory2D(const DeviceMemory2D& other_arg); /** \brief Assigment operator. Just increments reference counter. */ DeviceMemory2D& operator=(const DeviceMemory2D& other_arg); /** \brief Allocates internal buffer in GPU memory. If internal buffer was created before the function recreates it with new size. If new and old sizes are equal it does nothing. * \param ptr_arg: number of rows to allocate * \param sizeBytes_arg: width of the buffer in bytes * */ void create(int rows_arg, int colsBytes_arg); /** \brief Decrements reference counter and releases internal buffer if needed. */ void release(); /** \brief Performs data copying. If destination size differs it will be reallocated. * \param other_arg: destination container * */ void copyTo(DeviceMemory2D& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to ensure that intenal buffer size is enough. * \param host_ptr_arg: pointer to host buffer to upload * \param host_step_arg: stride between two consecutive rows in bytes for host buffer * \param rows_arg: number of rows to upload * \param sizeBytes_arg: width of host buffer in bytes * */ void upload(const void *host_ptr_arg, size_t host_step_arg, int rows_arg, int colsBytes_arg); /** \brief Downloads data from internal buffer to CPU memory. User is resposible for correct host buffer size. * \param host_ptr_arg: pointer to host buffer to download * \param host_step_arg: stride between two consecutive rows in bytes for host buffer * */ void download(void *host_ptr_arg, size_t host_step_arg) const; /** \brief Performs swap of data pointed with another device memory. * \param other: device memory to swap with * */ void swap(DeviceMemory2D& other_arg); /** \brief Returns pointer to given row in internal buffer. * \param y_arg: row index * */ template T* ptr(int y_arg = 0); /** \brief Returns constant pointer to given row in internal buffer. * \param y_arg: row index * */ template const T* ptr(int y_arg = 0) const; /** \brief Conversion to PtrStep for passing to kernel functions. */ template operator PtrStep() const; /** \brief Conversion to PtrStepSz for passing to kernel functions. */ template operator PtrStepSz() const; /** \brief Returns true if unallocated otherwise false. */ bool empty() const; /** \brief Returns number of bytes in each row. */ int colsBytes() const; /** \brief Returns number of rows. */ int rows() const; /** \brief Returns stride between two consecutive rows in bytes for internal buffer. Step is stored always and everywhere in bytes!!! */ size_t step() const; private: /** \brief Device pointer. */ void *data_; /** \brief Stride between two consecutive rows in bytes for internal buffer. Step is stored always and everywhere in bytes!!! */ size_t step_; /** \brief Width of the buffer in bytes. */ int colsBytes_; /** \brief Number of rows. */ int rows_; /** \brief Pointer to reference counter in CPU memory. */ int* refcount_; }; #include "device_memory_impl.hpp" #endif /* DEVICE_MEMORY_HPP_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/device_memory_impl.hpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef DEVICE_MEMORY_IMPL_HPP_ #define DEVICE_MEMORY_IMPL_HPP_ ///////////////////// Inline implementations of DeviceMemory //////////////////////////////////////////// template inline T* DeviceMemory::ptr() { return ( T*)data_; } template inline const T* DeviceMemory::ptr() const { return (const T*)data_; } template inline DeviceMemory::operator PtrSz() const { PtrSz result; result.data = (U*)ptr(); result.size = sizeBytes_/sizeof(U); return result; } ///////////////////// Inline implementations of DeviceMemory2D //////////////////////////////////////////// template T* DeviceMemory2D::ptr(int y_arg) { return ( T*)(( char*)data_ + y_arg * step_); } template const T* DeviceMemory2D::ptr(int y_arg) const { return (const T*)((const char*)data_ + y_arg * step_); } template DeviceMemory2D::operator PtrStep() const { PtrStep result; result.data = (U*)ptr(); result.step = step_; return result; } template DeviceMemory2D::operator PtrStepSz() const { PtrStepSz result; result.data = (U*)ptr(); result.step = step_; result.cols = colsBytes_/sizeof(U); result.rows = rows_; return result; } #endif /* DEVICE_MEMORY_IMPL_HPP_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/containers/kernel_containers.hpp ================================================ /* * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef KERNEL_CONTAINERS_HPP_ #define KERNEL_CONTAINERS_HPP_ #include #if defined(__CUDACC__) #define GPU_HOST_DEVICE__ __host__ __device__ __forceinline__ #else #define GPU_HOST_DEVICE__ #endif template struct DevPtr { typedef T elem_type; const static size_t elem_size = sizeof(elem_type); T* data; GPU_HOST_DEVICE__ DevPtr() : data(0) {} GPU_HOST_DEVICE__ DevPtr(T* data_arg) : data(data_arg) {} GPU_HOST_DEVICE__ size_t elemSize() const { return elem_size; } GPU_HOST_DEVICE__ operator T*() { return data; } GPU_HOST_DEVICE__ operator const T*() const { return data; } }; template struct PtrSz : public DevPtr { GPU_HOST_DEVICE__ PtrSz() : size(0) {} GPU_HOST_DEVICE__ PtrSz(T* data_arg, size_t size_arg) : DevPtr(data_arg), size(size_arg) {} size_t size; }; template struct PtrStep : public DevPtr { GPU_HOST_DEVICE__ PtrStep() : step(0) {} GPU_HOST_DEVICE__ PtrStep(T* data_arg, size_t step_arg) : DevPtr(data_arg), step(step_arg) {} /** \brief stride between two consecutive rows in bytes. Step is stored always and everywhere in bytes!!! */ size_t step; GPU_HOST_DEVICE__ T* ptr(int y = 0) { return ( T*)( ( char*)DevPtr::data + y * step); } GPU_HOST_DEVICE__ const T* ptr(int y = 0) const { return (const T*)( (const char*)DevPtr::data + y * step); } }; template struct PtrStepSz : public PtrStep { GPU_HOST_DEVICE__ PtrStepSz() : cols(0), rows(0) {} GPU_HOST_DEVICE__ PtrStepSz(int rows_arg, int cols_arg, T* data_arg, size_t step_arg) : PtrStep(data_arg, step_arg), cols(cols_arg), rows(rows_arg) {} int cols; int rows; }; #endif /* KERNEL_CONTAINERS_HPP_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/convenience.cuh ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef CUDA_CONVENIENCE_CUH_ #define CUDA_CONVENIENCE_CUH_ #include #include #include static inline int getGridDim(int x, int y) { return (x + y - 1) / y; } static inline void cudaSafeCall(cudaError_t err) { if(cudaSuccess != err) { std::cout << "Error: " << cudaGetErrorString(err) << ": " << __FILE__ << ":" << __LINE__ << std::endl; exit(0); } } #endif /* CUDA_CONVENIENCE_CUH_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/cudafuncs.cu ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #include "cudafuncs.cuh" #include "convenience.cuh" #include "operators.cuh" __global__ void pyrDownGaussKernel (const PtrStepSz src, PtrStepSz dst, float sigma_color) { int x = blockIdx.x * blockDim.x + threadIdx.x; int y = blockIdx.y * blockDim.y + threadIdx.y; if (x >= dst.cols || y >= dst.rows) return; const int D = 5; int center = src.ptr (2 * y)[2 * x]; int x_mi = max(0, 2*x - D/2) - 2*x; int y_mi = max(0, 2*y - D/2) - 2*y; int x_ma = min(src.cols, 2*x -D/2+D) - 2*x; int y_ma = min(src.rows, 2*y -D/2+D) - 2*y; float sum = 0; float wall = 0; float weights[] = {0.375f, 0.25f, 0.0625f} ; for(int yi = y_mi; yi < y_ma; ++yi) for(int xi = x_mi; xi < x_ma; ++xi) { int val = src.ptr (2*y + yi)[2*x + xi]; if (abs (val - center) < 3 * sigma_color) { sum += val * weights[abs(xi)] * weights[abs(yi)]; wall += weights[abs(xi)] * weights[abs(yi)]; } } dst.ptr (y)[x] = static_cast(sum /wall); } void pyrDown(const DeviceArray2D & src, DeviceArray2D & dst) { dst.create (src.rows () / 2, src.cols () / 2); dim3 block (32, 8); dim3 grid (getGridDim (dst.cols (), block.x), getGridDim (dst.rows (), block.y)); const float sigma_color = 30; pyrDownGaussKernel<<>>(src, dst, sigma_color); cudaSafeCall ( cudaGetLastError () ); }; __global__ void computeVmapKernel(const PtrStepSz depth, PtrStep vmap, float fx_inv, float fy_inv, float cx, float cy, float depthCutoff) { int u = threadIdx.x + blockIdx.x * blockDim.x; int v = threadIdx.y + blockIdx.y * blockDim.y; if(u < depth.cols && v < depth.rows) { float z = depth.ptr (v)[u] / 1000.f; // load and convert: mm -> meters if(z != 0 && z < depthCutoff) { float vx = z * (u - cx) * fx_inv; float vy = z * (v - cy) * fy_inv; float vz = z; vmap.ptr (v )[u] = vx; vmap.ptr (v + depth.rows )[u] = vy; vmap.ptr (v + depth.rows * 2)[u] = vz; } else { vmap.ptr (v)[u] = __int_as_float(0x7fffffff); /*CUDART_NAN_F*/ } } } void createVMap(const CameraModel& intr, const DeviceArray2D & depth, DeviceArray2D & vmap, const float depthCutoff) { vmap.create (depth.rows () * 3, depth.cols ()); dim3 block (32, 8); dim3 grid (1, 1, 1); grid.x = getGridDim (depth.cols (), block.x); grid.y = getGridDim (depth.rows (), block.y); float fx = intr.fx, cx = intr.cx; float fy = intr.fy, cy = intr.cy; computeVmapKernel<<>>(depth, vmap, 1.f / fx, 1.f / fy, cx, cy, depthCutoff); cudaSafeCall (cudaGetLastError ()); } __global__ void computeNmapKernel(int rows, int cols, const PtrStep vmap, PtrStep nmap) { int u = threadIdx.x + blockIdx.x * blockDim.x; int v = threadIdx.y + blockIdx.y * blockDim.y; if (u >= cols || v >= rows) return; if (u == cols - 1 || v == rows - 1) { nmap.ptr (v)[u] = __int_as_float(0x7fffffff); /*CUDART_NAN_F*/ return; } float3 v00, v01, v10; v00.x = vmap.ptr (v )[u]; v01.x = vmap.ptr (v )[u + 1]; v10.x = vmap.ptr (v + 1)[u]; if (!isnan (v00.x) && !isnan (v01.x) && !isnan (v10.x)) { v00.y = vmap.ptr (v + rows)[u]; v01.y = vmap.ptr (v + rows)[u + 1]; v10.y = vmap.ptr (v + 1 + rows)[u]; v00.z = vmap.ptr (v + 2 * rows)[u]; v01.z = vmap.ptr (v + 2 * rows)[u + 1]; v10.z = vmap.ptr (v + 1 + 2 * rows)[u]; float3 r = normalized (cross (v01 - v00, v10 - v00)); nmap.ptr (v )[u] = r.x; nmap.ptr (v + rows)[u] = r.y; nmap.ptr (v + 2 * rows)[u] = r.z; } else nmap.ptr (v)[u] = __int_as_float(0x7fffffff); /*CUDART_NAN_F*/ } void createNMap(const DeviceArray2D& vmap, DeviceArray2D& nmap) { nmap.create (vmap.rows (), vmap.cols ()); int rows = vmap.rows () / 3; int cols = vmap.cols (); dim3 block (32, 8); dim3 grid (1, 1, 1); grid.x = getGridDim (cols, block.x); grid.y = getGridDim (rows, block.y); computeNmapKernel<<>>(rows, cols, vmap, nmap); cudaSafeCall (cudaGetLastError ()); } __global__ void tranformMapsKernel(int rows, int cols, const PtrStep vmap_src, const PtrStep nmap_src, const mat33 Rmat, const float3 tvec, PtrStepSz vmap_dst, PtrStep nmap_dst) { int x = threadIdx.x + blockIdx.x * blockDim.x; int y = threadIdx.y + blockIdx.y * blockDim.y; if (x < cols && y < rows) { //vertexes float3 vsrc, vdst = make_float3 (__int_as_float(0x7fffffff), __int_as_float(0x7fffffff), __int_as_float(0x7fffffff)); vsrc.x = vmap_src.ptr (y)[x]; if (!isnan (vsrc.x)) { vsrc.y = vmap_src.ptr (y + rows)[x]; vsrc.z = vmap_src.ptr (y + 2 * rows)[x]; vdst = Rmat * vsrc + tvec; vmap_dst.ptr (y + rows)[x] = vdst.y; vmap_dst.ptr (y + 2 * rows)[x] = vdst.z; } vmap_dst.ptr (y)[x] = vdst.x; //normals float3 nsrc, ndst = make_float3 (__int_as_float(0x7fffffff), __int_as_float(0x7fffffff), __int_as_float(0x7fffffff)); nsrc.x = nmap_src.ptr (y)[x]; if (!isnan (nsrc.x)) { nsrc.y = nmap_src.ptr (y + rows)[x]; nsrc.z = nmap_src.ptr (y + 2 * rows)[x]; ndst = Rmat * nsrc; nmap_dst.ptr (y + rows)[x] = ndst.y; nmap_dst.ptr (y + 2 * rows)[x] = ndst.z; } nmap_dst.ptr (y)[x] = ndst.x; } } void tranformMaps(const DeviceArray2D& vmap_src, const DeviceArray2D& nmap_src, const mat33& Rmat, const float3& tvec, DeviceArray2D& vmap_dst, DeviceArray2D& nmap_dst) { int cols = vmap_src.cols(); int rows = vmap_src.rows() / 3; vmap_dst.create(rows * 3, cols); nmap_dst.create(rows * 3, cols); dim3 block(32, 8); dim3 grid(1, 1, 1); grid.x = getGridDim(cols, block.x); grid.y = getGridDim(rows, block.y); tranformMapsKernel<<>>(rows, cols, vmap_src, nmap_src, Rmat, tvec, vmap_dst, nmap_dst); cudaSafeCall(cudaGetLastError()); } __global__ void copyMapsKernel(int rows, int cols, const float * vmap_src, const float * nmap_src, PtrStepSz vmap_dst, PtrStep nmap_dst) { int x = threadIdx.x + blockIdx.x * blockDim.x; int y = threadIdx.y + blockIdx.y * blockDim.y; if (x < cols && y < rows) { //vertexes float3 vsrc, vdst = make_float3 (__int_as_float(0x7fffffff), __int_as_float(0x7fffffff), __int_as_float(0x7fffffff)); vsrc.x = vmap_src[y * cols * 4 + (x * 4) + 0]; vsrc.y = vmap_src[y * cols * 4 + (x * 4) + 1]; vsrc.z = vmap_src[y * cols * 4 + (x * 4) + 2]; if(!(vsrc.z == 0)) { vdst = vsrc; } vmap_dst.ptr (y)[x] = vdst.x; vmap_dst.ptr (y + rows)[x] = vdst.y; vmap_dst.ptr (y + 2 * rows)[x] = vdst.z; //normals float3 nsrc, ndst = make_float3 (__int_as_float(0x7fffffff), __int_as_float(0x7fffffff), __int_as_float(0x7fffffff)); nsrc.x = nmap_src[y * cols * 4 + (x * 4) + 0]; nsrc.y = nmap_src[y * cols * 4 + (x * 4) + 1]; nsrc.z = nmap_src[y * cols * 4 + (x * 4) + 2]; if(!(vsrc.z == 0)) { ndst = nsrc; } nmap_dst.ptr (y)[x] = ndst.x; nmap_dst.ptr (y + rows)[x] = ndst.y; nmap_dst.ptr (y + 2 * rows)[x] = ndst.z; } } void copyMaps(const DeviceArray& vmap_src, const DeviceArray& nmap_src, DeviceArray2D& vmap_dst, DeviceArray2D& nmap_dst) { int cols = vmap_dst.cols(); int rows = vmap_dst.rows() / 3; vmap_dst.create(rows * 3, cols); nmap_dst.create(rows * 3, cols); dim3 block(32, 8); dim3 grid(1, 1, 1); grid.x = getGridDim(cols, block.x); grid.y = getGridDim(rows, block.y); copyMapsKernel<<>>(rows, cols, vmap_src, nmap_src, vmap_dst, nmap_dst); cudaSafeCall(cudaGetLastError()); } __global__ void pyrDownKernelGaussF(const PtrStepSz src, PtrStepSz dst, float * gaussKernel) { int x = blockIdx.x * blockDim.x + threadIdx.x; int y = blockIdx.y * blockDim.y + threadIdx.y; if (x >= dst.cols || y >= dst.rows) return; const int D = 5; float center = src.ptr (2 * y)[2 * x]; int tx = min (2 * x - D / 2 + D, src.cols - 1); int ty = min (2 * y - D / 2 + D, src.rows - 1); int cy = max (0, 2 * y - D / 2); float sum = 0; int count = 0; for (; cy < ty; ++cy) { for (int cx = max (0, 2 * x - D / 2); cx < tx; ++cx) { if(!isnan(src.ptr (cy)[cx])) { sum += src.ptr (cy)[cx] * gaussKernel[(ty - cy - 1) * 5 + (tx - cx - 1)]; count += gaussKernel[(ty - cy - 1) * 5 + (tx - cx - 1)]; } } } dst.ptr (y)[x] = (float)(sum / (float)count); } template __global__ void resizeMapKernel(int drows, int dcols, int srows, const PtrStep input, PtrStep output) { int x = threadIdx.x + blockIdx.x * blockDim.x; int y = threadIdx.y + blockIdx.y * blockDim.y; if (x >= dcols || y >= drows) return; const float qnan = __int_as_float(0x7fffffff); int xs = x * 2; int ys = y * 2; float x00 = input.ptr (ys + 0)[xs + 0]; float x01 = input.ptr (ys + 0)[xs + 1]; float x10 = input.ptr (ys + 1)[xs + 0]; float x11 = input.ptr (ys + 1)[xs + 1]; if (isnan (x00) || isnan (x01) || isnan (x10) || isnan (x11)) { output.ptr (y)[x] = qnan; return; } else { float3 n; n.x = (x00 + x01 + x10 + x11) / 4; float y00 = input.ptr (ys + srows + 0)[xs + 0]; float y01 = input.ptr (ys + srows + 0)[xs + 1]; float y10 = input.ptr (ys + srows + 1)[xs + 0]; float y11 = input.ptr (ys + srows + 1)[xs + 1]; n.y = (y00 + y01 + y10 + y11) / 4; float z00 = input.ptr (ys + 2 * srows + 0)[xs + 0]; float z01 = input.ptr (ys + 2 * srows + 0)[xs + 1]; float z10 = input.ptr (ys + 2 * srows + 1)[xs + 0]; float z11 = input.ptr (ys + 2 * srows + 1)[xs + 1]; n.z = (z00 + z01 + z10 + z11) / 4; if (normalize) n = normalized (n); output.ptr (y )[x] = n.x; output.ptr (y + drows)[x] = n.y; output.ptr (y + 2 * drows)[x] = n.z; } } template void resizeMap(const DeviceArray2D& input, DeviceArray2D& output) { int in_cols = input.cols (); int in_rows = input.rows () / 3; int out_cols = in_cols / 2; int out_rows = in_rows / 2; output.create (out_rows * 3, out_cols); dim3 block (32, 8); dim3 grid (getGridDim (out_cols, block.x), getGridDim (out_rows, block.y)); resizeMapKernel<< < grid, block>>>(out_rows, out_cols, in_rows, input, output); cudaSafeCall ( cudaGetLastError () ); cudaSafeCall (cudaDeviceSynchronize ()); } void resizeVMap(const DeviceArray2D& input, DeviceArray2D& output) { resizeMap(input, output); } void resizeNMap(const DeviceArray2D& input, DeviceArray2D& output) { resizeMap(input, output); } void pyrDownGaussF(const DeviceArray2D& src, DeviceArray2D & dst) { dst.create (src.rows () / 2, src.cols () / 2); dim3 block (32, 8); dim3 grid (getGridDim (dst.cols (), block.x), getGridDim (dst.rows (), block.y)); const float gaussKernel[25] = {1, 4, 6, 4, 1, 4, 16, 24, 16, 4, 6, 24, 36, 24, 6, 4, 16, 24, 16, 4, 1, 4, 6, 4, 1}; float * gauss_cuda; cudaMalloc((void**) &gauss_cuda, sizeof(float) * 25); cudaMemcpy(gauss_cuda, &gaussKernel[0], sizeof(float) * 25, cudaMemcpyHostToDevice); pyrDownKernelGaussF<<>>(src, dst, gauss_cuda); cudaSafeCall ( cudaGetLastError () ); cudaFree(gauss_cuda); }; __global__ void pyrDownKernelIntensityGauss(const PtrStepSz src, PtrStepSz dst, float * gaussKernel) { int x = blockIdx.x * blockDim.x + threadIdx.x; int y = blockIdx.y * blockDim.y + threadIdx.y; if (x >= dst.cols || y >= dst.rows) return; const int D = 5; int center = src.ptr (2 * y)[2 * x]; int tx = min (2 * x - D / 2 + D, src.cols - 1); int ty = min (2 * y - D / 2 + D, src.rows - 1); int cy = max (0, 2 * y - D / 2); float sum = 0; int count = 0; for (; cy < ty; ++cy) for (int cx = max (0, 2 * x - D / 2); cx < tx; ++cx) { //This might not be right, but it stops incomplete model images from making up colors if(src.ptr (cy)[cx] > 0) { sum += src.ptr (cy)[cx] * gaussKernel[(ty - cy - 1) * 5 + (tx - cx - 1)]; count += gaussKernel[(ty - cy - 1) * 5 + (tx - cx - 1)]; } } dst.ptr (y)[x] = (sum / (float)count); } void pyrDownUcharGauss(const DeviceArray2D& src, DeviceArray2D & dst) { dst.create (src.rows () / 2, src.cols () / 2); dim3 block (32, 8); dim3 grid (getGridDim (dst.cols (), block.x), getGridDim (dst.rows (), block.y)); const float gaussKernel[25] = {1, 4, 6, 4, 1, 4, 16, 24, 16, 4, 6, 24, 36, 24, 6, 4, 16, 24, 16, 4, 1, 4, 6, 4, 1}; float * gauss_cuda; cudaMalloc((void**) &gauss_cuda, sizeof(float) * 25); cudaMemcpy(gauss_cuda, &gaussKernel[0], sizeof(float) * 25, cudaMemcpyHostToDevice); pyrDownKernelIntensityGauss<<>>(src, dst, gauss_cuda); cudaSafeCall ( cudaGetLastError () ); cudaFree(gauss_cuda); }; __global__ void verticesToDepthKernel(const float * vmap_src, PtrStepSz dst, float cutOff) { int x = blockIdx.x * blockDim.x + threadIdx.x; int y = blockIdx.y * blockDim.y + threadIdx.y; if (x >= dst.cols || y >= dst.rows) return; float z = vmap_src[y * dst.cols * 4 + (x * 4) + 2]; dst.ptr(y)[x] = z > cutOff || z <= 0 ? __int_as_float(0x7fffffff)/*CUDART_NAN_F*/ : z; } void verticesToDepth(DeviceArray& vmap_src, DeviceArray2D & dst, float cutOff) { dim3 block (32, 8); dim3 grid (getGridDim (dst.cols (), block.x), getGridDim (dst.rows (), block.y)); verticesToDepthKernel<<>>(vmap_src, dst, cutOff); cudaSafeCall ( cudaGetLastError () ); }; texture inTex; __global__ void bgr2IntensityKernel(PtrStepSz dst) { int x = blockIdx.x * blockDim.x + threadIdx.x; int y = blockIdx.y * blockDim.y + threadIdx.y; if (x >= dst.cols || y >= dst.rows) return; uchar4 src = tex2D(inTex, x, y); int value = (float)src.x * 0.114f + (float)src.y * 0.299f + (float)src.z * 0.587f; dst.ptr (y)[x] = value; } void imageBGRToIntensity(cudaArray * cuArr, DeviceArray2D & dst) { dim3 block (32, 8); dim3 grid (getGridDim (dst.cols (), block.x), getGridDim (dst.rows (), block.y)); cudaSafeCall(cudaBindTextureToArray(inTex, cuArr)); bgr2IntensityKernel<<>>(dst); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaUnbindTexture(inTex)); }; __constant__ float gsobel_x3x3[9]; __constant__ float gsobel_y3x3[9]; __global__ void applyKernel(const PtrStepSz src, PtrStep dx, PtrStep dy) { int x = threadIdx.x + blockIdx.x * blockDim.x; int y = threadIdx.y + blockIdx.y * blockDim.y; if(x >= src.cols || y >= src.rows) return; float dxVal = 0; float dyVal = 0; int kernelIndex = 8; for(int j = max(y - 1, 0); j <= min(y + 1, src.rows - 1); j++) { for(int i = max(x - 1, 0); i <= min(x + 1, src.cols - 1); i++) { dxVal += (float)src.ptr(j)[i] * gsobel_x3x3[kernelIndex]; dyVal += (float)src.ptr(j)[i] * gsobel_y3x3[kernelIndex]; --kernelIndex; } } dx.ptr(y)[x] = dxVal; dy.ptr(y)[x] = dyVal; } void computeDerivativeImages(DeviceArray2D& src, DeviceArray2D& dx, DeviceArray2D& dy) { static bool once = false; if(!once) { float gsx3x3[9] = {0.52201, 0.00000, -0.52201, 0.79451, -0.00000, -0.79451, 0.52201, 0.00000, -0.52201}; float gsy3x3[9] = {0.52201, 0.79451, 0.52201, 0.00000, 0.00000, 0.00000, -0.52201, -0.79451, -0.52201}; cudaMemcpyToSymbol(gsobel_x3x3, gsx3x3, sizeof(float) * 9); cudaMemcpyToSymbol(gsobel_y3x3, gsy3x3, sizeof(float) * 9); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); once = true; } dim3 block(32, 8); dim3 grid(getGridDim (src.cols (), block.x), getGridDim (src.rows (), block.y)); applyKernel<<>>(src, dx, dy); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); } __global__ void projectPointsKernel(const PtrStepSz depth, PtrStepSz cloud, const float invFx, const float invFy, const float cx, const float cy) { int x = threadIdx.x + blockIdx.x * blockDim.x; int y = threadIdx.y + blockIdx.y * blockDim.y; if (x >= depth.cols || y >= depth.rows) return; float z = depth.ptr(y)[x]; cloud.ptr(y)[x].x = (float)((x - cx) * z * invFx); cloud.ptr(y)[x].y = (float)((y - cy) * z * invFy); cloud.ptr(y)[x].z = z; } void projectToPointCloud(const DeviceArray2D & depth, const DeviceArray2D & cloud, CameraModel & intrinsics, const int & level) { dim3 block (32, 8); dim3 grid (getGridDim (depth.cols (), block.x), getGridDim (depth.rows (), block.y)); CameraModel intrinsicsLevel = intrinsics(level); projectPointsKernel<<>>(depth, cloud, 1.0f / intrinsicsLevel.fx, 1.0f / intrinsicsLevel.fy, intrinsicsLevel.cx, intrinsicsLevel.cy); cudaSafeCall ( cudaGetLastError () ); cudaSafeCall (cudaDeviceSynchronize ()); } ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/cudafuncs.cuh ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef CUDA_CUDAFUNCS_CUH_ #define CUDA_CUDAFUNCS_CUH_ #if __CUDA_ARCH__ < 300 #define MAX_THREADS 512 #else #define MAX_THREADS 1024 #endif #include "containers/device_array.hpp" #include "types.cuh" void icpStep(const mat33& Rcurr, const float3& tcurr, const DeviceArray2D& vmap_curr, const DeviceArray2D& nmap_curr, const mat33& Rprev_inv, const float3& tprev, const CameraModel& intr, const DeviceArray2D& vmap_g_prev, const DeviceArray2D& nmap_g_prev, float distThres, float angleThres, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, float * residual_host, int threads, int blocks); void rgbStep(const DeviceArray2D & corresImg, const float & sigma, const DeviceArray2D & cloud, const float & fx, const float & fy, const DeviceArray2D & dIdx, const DeviceArray2D & dIdy, const float & sobelScale, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, int threads, int blocks); void so3Step(const DeviceArray2D & lastImage, const DeviceArray2D & nextImage, const mat33 & imageBasis, const mat33 & kinv, const mat33 & krlr, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, float * residual_host, int threads, int blocks); void computeRgbResidual(const float & minScale, const DeviceArray2D & dIdx, const DeviceArray2D & dIdy, const DeviceArray2D & lastDepth, const DeviceArray2D & nextDepth, const DeviceArray2D & lastImage, const DeviceArray2D & nextImage, DeviceArray2D & corresImg, DeviceArray & sumResidual, const float maxDepthDelta, const float3 & kt, const mat33 & krkinv, int & sigmaSum, int & count, int threads, int blocks); void createVMap(const CameraModel& intr, const DeviceArray2D & depth, DeviceArray2D & vmap, const float depthCutoff); void createNMap(const DeviceArray2D& vmap, DeviceArray2D& nmap); void tranformMaps(const DeviceArray2D& vmap_src, const DeviceArray2D& nmap_src, const mat33& Rmat, const float3& tvec, DeviceArray2D& vmap_dst, DeviceArray2D& nmap_dst); void copyMaps(const DeviceArray& vmap_src, const DeviceArray& nmap_src, DeviceArray2D& vmap_dst, DeviceArray2D& nmap_dst); void resizeVMap(const DeviceArray2D& input, DeviceArray2D& output); void resizeNMap(const DeviceArray2D& input, DeviceArray2D& output); void imageBGRToIntensity(cudaArray * cuArr, DeviceArray2D & dst); void verticesToDepth(DeviceArray& vmap_src, DeviceArray2D & dst, float cutOff); void projectToPointCloud(const DeviceArray2D & depth, const DeviceArray2D & cloud, CameraModel & intrinsics, const int & level); void pyrDown(const DeviceArray2D & src, DeviceArray2D & dst); void pyrDownGaussF(const DeviceArray2D & src, DeviceArray2D & dst); void pyrDownUcharGauss(const DeviceArray2D& src, DeviceArray2D & dst); void computeDerivativeImages(DeviceArray2D& src, DeviceArray2D& dx, DeviceArray2D& dy); #endif /* CUDA_CUDAFUNCS_CUH_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/operators.cuh ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #include #ifndef CUDA_OPERATORS_CUH_ #define CUDA_OPERATORS_CUH_ __device__ __host__ __forceinline__ float3 operator-(const float3& a, const float3& b) { return make_float3(a.x - b.x, a.y - b.y, a.z - b.z); } __device__ __host__ __forceinline__ float3 operator+(const float3& a, const float3& b) { return make_float3(a.x + b.x, a.y + b.y, a.z + b.z); } __device__ __host__ __forceinline__ float3 cross(const float3& a, const float3& b) { return make_float3(a.y * b.z - a.z * b.y, a.z * b.x - a.x * b.z, a.x * b.y - a.y * b.x); } __device__ __host__ __forceinline__ float dot(const float3& a, const float3& b) { return a.x * b.x + a.y * b.y + a.z * b.z; } __device__ __host__ __forceinline__ float norm(const float3& a) { return sqrtf(dot(a, a)); } __device__ __host__ __forceinline__ float3 normalized(const float3& a) { const float rn = rsqrtf(dot(a, a)); return make_float3(a.x * rn, a.y * rn, a.z * rn); } __device__ __forceinline__ float3 operator*(const mat33& m, const float3& a) { return make_float3(dot(m.data[0], a), dot(m.data[1], a), dot(m.data[2], a)); } #endif /* CUDA_OPERATORS_CUH_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/reduce.cu ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #include "cudafuncs.cuh" #include "convenience.cuh" #include "operators.cuh" #if __CUDA_ARCH__ < 300 __inline__ __device__ float __shfl_down(float val, int offset, int width = 32) { static __shared__ float shared[MAX_THREADS]; int lane = threadIdx.x % 32; shared[threadIdx.x] = val; __syncthreads(); val = (lane + offset < width) ? shared[threadIdx.x + offset] : 0; __syncthreads(); return val; } __inline__ __device__ int __shfl_down(int val, int offset, int width = 32) { static __shared__ int shared[MAX_THREADS]; int lane = threadIdx.x % 32; shared[threadIdx.x] = val; __syncthreads(); val = (lane + offset < width) ? shared[threadIdx.x + offset] : 0; __syncthreads(); return val; } #endif #if __CUDA_ARCH__ < 350 template __device__ __forceinline__ T __ldg(const T* ptr) { return *ptr; } #endif __inline__ __device__ JtJJtrSE3 warpReduceSum(JtJJtrSE3 val) { for(int offset = warpSize / 2; offset > 0; offset /= 2) { val.aa += __shfl_down(val.aa, offset); val.ab += __shfl_down(val.ab, offset); val.ac += __shfl_down(val.ac, offset); val.ad += __shfl_down(val.ad, offset); val.ae += __shfl_down(val.ae, offset); val.af += __shfl_down(val.af, offset); val.ag += __shfl_down(val.ag, offset); val.bb += __shfl_down(val.bb, offset); val.bc += __shfl_down(val.bc, offset); val.bd += __shfl_down(val.bd, offset); val.be += __shfl_down(val.be, offset); val.bf += __shfl_down(val.bf, offset); val.bg += __shfl_down(val.bg, offset); val.cc += __shfl_down(val.cc, offset); val.cd += __shfl_down(val.cd, offset); val.ce += __shfl_down(val.ce, offset); val.cf += __shfl_down(val.cf, offset); val.cg += __shfl_down(val.cg, offset); val.dd += __shfl_down(val.dd, offset); val.de += __shfl_down(val.de, offset); val.df += __shfl_down(val.df, offset); val.dg += __shfl_down(val.dg, offset); val.ee += __shfl_down(val.ee, offset); val.ef += __shfl_down(val.ef, offset); val.eg += __shfl_down(val.eg, offset); val.ff += __shfl_down(val.ff, offset); val.fg += __shfl_down(val.fg, offset); val.residual += __shfl_down(val.residual, offset); val.inliers += __shfl_down(val.inliers, offset); } return val; } __inline__ __device__ JtJJtrSE3 blockReduceSum(JtJJtrSE3 val) { static __shared__ JtJJtrSE3 shared[32]; int lane = threadIdx.x % warpSize; int wid = threadIdx.x / warpSize; val = warpReduceSum(val); //write reduced value to shared memory if(lane == 0) { shared[wid] = val; } __syncthreads(); const JtJJtrSE3 zero = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; //ensure we only grab a value from shared memory if that warp existed val = (threadIdx.x < blockDim.x / warpSize) ? shared[lane] : zero; if(wid == 0) { val = warpReduceSum(val); } return val; } __global__ void reduceSum(JtJJtrSE3 * in, JtJJtrSE3 * out, int N) { JtJJtrSE3 sum = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { sum.add(in[i]); } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } __inline__ __device__ JtJJtrSO3 warpReduceSum(JtJJtrSO3 val) { for(int offset = warpSize / 2; offset > 0; offset /= 2) { val.aa += __shfl_down(val.aa, offset); val.ab += __shfl_down(val.ab, offset); val.ac += __shfl_down(val.ac, offset); val.ad += __shfl_down(val.ad, offset); val.bb += __shfl_down(val.bb, offset); val.bc += __shfl_down(val.bc, offset); val.bd += __shfl_down(val.bd, offset); val.cc += __shfl_down(val.cc, offset); val.cd += __shfl_down(val.cd, offset); val.residual += __shfl_down(val.residual, offset); val.inliers += __shfl_down(val.inliers, offset); } return val; } __inline__ __device__ JtJJtrSO3 blockReduceSum(JtJJtrSO3 val) { static __shared__ JtJJtrSO3 shared[32]; int lane = threadIdx.x % warpSize; int wid = threadIdx.x / warpSize; val = warpReduceSum(val); //write reduced value to shared memory if(lane == 0) { shared[wid] = val; } __syncthreads(); const JtJJtrSO3 zero = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; //ensure we only grab a value from shared memory if that warp existed val = (threadIdx.x < blockDim.x / warpSize) ? shared[lane] : zero; if(wid == 0) { val = warpReduceSum(val); } return val; } __global__ void reduceSum(JtJJtrSO3 * in, JtJJtrSO3 * out, int N) { JtJJtrSO3 sum = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { sum.add(in[i]); } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } struct ICPReduction { mat33 Rcurr; float3 tcurr; PtrStep vmap_curr; PtrStep nmap_curr; mat33 Rprev_inv; float3 tprev; CameraModel intr; PtrStep vmap_g_prev; PtrStep nmap_g_prev; float distThres; float angleThres; int cols; int rows; int N; JtJJtrSE3 * out; __device__ __forceinline__ bool search (int & x, int & y, float3& n, float3& d, float3& s) const { float3 vcurr; vcurr.x = vmap_curr.ptr (y )[x]; vcurr.y = vmap_curr.ptr (y + rows)[x]; vcurr.z = vmap_curr.ptr (y + 2 * rows)[x]; float3 vcurr_g = Rcurr * vcurr + tcurr; float3 vcurr_cp = Rprev_inv * (vcurr_g - tprev); int2 ukr; ukr.x = __float2int_rn (vcurr_cp.x * intr.fx / vcurr_cp.z + intr.cx); ukr.y = __float2int_rn (vcurr_cp.y * intr.fy / vcurr_cp.z + intr.cy); if(ukr.x < 0 || ukr.y < 0 || ukr.x >= cols || ukr.y >= rows || vcurr_cp.z < 0) return false; float3 vprev_g; vprev_g.x = __ldg(&vmap_g_prev.ptr (ukr.y )[ukr.x]); vprev_g.y = __ldg(&vmap_g_prev.ptr (ukr.y + rows)[ukr.x]); vprev_g.z = __ldg(&vmap_g_prev.ptr (ukr.y + 2 * rows)[ukr.x]); float3 ncurr; ncurr.x = nmap_curr.ptr (y)[x]; ncurr.y = nmap_curr.ptr (y + rows)[x]; ncurr.z = nmap_curr.ptr (y + 2 * rows)[x]; float3 ncurr_g = Rcurr * ncurr; float3 nprev_g; nprev_g.x = __ldg(&nmap_g_prev.ptr (ukr.y)[ukr.x]); nprev_g.y = __ldg(&nmap_g_prev.ptr (ukr.y + rows)[ukr.x]); nprev_g.z = __ldg(&nmap_g_prev.ptr (ukr.y + 2 * rows)[ukr.x]); float dist = norm (vprev_g - vcurr_g); float sine = norm (cross (ncurr_g, nprev_g)); n = nprev_g; d = vprev_g; s = vcurr_g; return (sine < angleThres && dist <= distThres && !isnan (ncurr.x) && !isnan (nprev_g.x)); } __device__ __forceinline__ JtJJtrSE3 getProducts(int & i) const { int y = i / cols; int x = i - (y * cols); float3 n_cp, d_cp, s_cp; bool found_coresp = search (x, y, n_cp, d_cp, s_cp); float row[7] = {0, 0, 0, 0, 0, 0, 0}; if(found_coresp) { s_cp = Rprev_inv * (s_cp - tprev); d_cp = Rprev_inv * (d_cp - tprev); n_cp = Rprev_inv * (n_cp); *(float3*)&row[0] = n_cp; *(float3*)&row[3] = cross (s_cp, n_cp); row[6] = dot (n_cp, s_cp - d_cp); } JtJJtrSE3 values = {row[0] * row[0], row[0] * row[1], row[0] * row[2], row[0] * row[3], row[0] * row[4], row[0] * row[5], row[0] * row[6], row[1] * row[1], row[1] * row[2], row[1] * row[3], row[1] * row[4], row[1] * row[5], row[1] * row[6], row[2] * row[2], row[2] * row[3], row[2] * row[4], row[2] * row[5], row[2] * row[6], row[3] * row[3], row[3] * row[4], row[3] * row[5], row[3] * row[6], row[4] * row[4], row[4] * row[5], row[4] * row[6], row[5] * row[5], row[5] * row[6], row[6] * row[6], found_coresp}; return values; } __device__ __forceinline__ void operator () () const { JtJJtrSE3 sum = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { JtJJtrSE3 val = getProducts(i); sum.add(val); } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } }; __global__ void icpKernel(const ICPReduction icp) { icp(); } void icpStep(const mat33& Rcurr, const float3& tcurr, const DeviceArray2D& vmap_curr, const DeviceArray2D& nmap_curr, const mat33& Rprev_inv, const float3& tprev, const CameraModel& intr, const DeviceArray2D& vmap_g_prev, const DeviceArray2D& nmap_g_prev, float distThres, float angleThres, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, float * residual_host, int threads, int blocks) { int cols = vmap_curr.cols (); int rows = vmap_curr.rows () / 3; ICPReduction icp; icp.Rcurr = Rcurr; icp.tcurr = tcurr; icp.vmap_curr = vmap_curr; icp.nmap_curr = nmap_curr; icp.Rprev_inv = Rprev_inv; icp.tprev = tprev; icp.intr = intr; icp.vmap_g_prev = vmap_g_prev; icp.nmap_g_prev = nmap_g_prev; icp.distThres = distThres; icp.angleThres = angleThres; icp.cols = cols; icp.rows = rows; icp.N = cols * rows; icp.out = sum; icpKernel<<>>(icp); reduceSum<<<1, MAX_THREADS>>>(sum, out, blocks); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); float host_data[32]; out.download((JtJJtrSE3 *)&host_data[0]); int shift = 0; for (int i = 0; i < 6; ++i) { for (int j = i; j < 7; ++j) { float value = host_data[shift++]; if (j == 6) vectorB_host[i] = value; else matrixA_host[j * 6 + i] = matrixA_host[i * 6 + j] = value; } } residual_host[0] = host_data[27]; residual_host[1] = host_data[28]; } #define FLT_EPSILON ((float)1.19209290E-07F) struct RGBReduction { PtrStepSz corresImg; float sigma; PtrStepSz cloud; float fx; float fy; PtrStepSz dIdx; PtrStepSz dIdy; float sobelScale; int cols; int rows; int N; JtJJtrSE3 * out; __device__ __forceinline__ JtJJtrSE3 getProducts(int & i) const { const DataTerm & corresp = corresImg.data[i]; bool found_coresp = corresp.valid; float row[7]; if(found_coresp) { float w = sigma + std::abs(corresp.diff); w = w > FLT_EPSILON ? 1.0f / w : 1.0f; //Signals RGB only tracking, so we should only if(sigma == -1) { w = 1; } row[6] = -w * corresp.diff; float3 cloudPoint = {cloud.ptr(corresp.zero.y)[corresp.zero.x].x, cloud.ptr(corresp.zero.y)[corresp.zero.x].y, cloud.ptr(corresp.zero.y)[corresp.zero.x].z}; float invz = 1.0 / cloudPoint.z; float dI_dx_val = w * sobelScale * dIdx.ptr(corresp.one.y)[corresp.one.x]; float dI_dy_val = w * sobelScale * dIdy.ptr(corresp.one.y)[corresp.one.x]; float v0 = dI_dx_val * fx * invz; float v1 = dI_dy_val * fy * invz; float v2 = -(v0 * cloudPoint.x + v1 * cloudPoint.y) * invz; row[0] = v0; row[1] = v1; row[2] = v2; row[3] = -cloudPoint.z * v1 + cloudPoint.y * v2; row[4] = cloudPoint.z * v0 - cloudPoint.x * v2; row[5] = -cloudPoint.y * v0 + cloudPoint.x * v1; } else { row[0] = row[1] = row[2] = row[3] = row[4] = row[5] = row[6] = 0.f; } JtJJtrSE3 values = {row[0] * row[0], row[0] * row[1], row[0] * row[2], row[0] * row[3], row[0] * row[4], row[0] * row[5], row[0] * row[6], row[1] * row[1], row[1] * row[2], row[1] * row[3], row[1] * row[4], row[1] * row[5], row[1] * row[6], row[2] * row[2], row[2] * row[3], row[2] * row[4], row[2] * row[5], row[2] * row[6], row[3] * row[3], row[3] * row[4], row[3] * row[5], row[3] * row[6], row[4] * row[4], row[4] * row[5], row[4] * row[6], row[5] * row[5], row[5] * row[6], row[6] * row[6], found_coresp}; return values; } __device__ __forceinline__ void operator () () const { JtJJtrSE3 sum = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { JtJJtrSE3 val = getProducts(i); sum.add(val); } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } }; __global__ void rgbKernel (const RGBReduction rgb) { rgb(); } void rgbStep(const DeviceArray2D & corresImg, const float & sigma, const DeviceArray2D & cloud, const float & fx, const float & fy, const DeviceArray2D & dIdx, const DeviceArray2D & dIdy, const float & sobelScale, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, int threads, int blocks) { RGBReduction rgb; rgb.corresImg = corresImg; rgb.cols = corresImg.cols(); rgb.rows = corresImg.rows(); rgb.sigma = sigma; rgb.cloud = cloud; rgb.fx = fx; rgb.fy = fy; rgb.dIdx = dIdx; rgb.dIdy = dIdy; rgb.sobelScale = sobelScale; rgb.N = rgb.cols * rgb.rows; rgb.out = sum; rgbKernel<<>>(rgb); reduceSum<<<1, MAX_THREADS>>>(sum, out, blocks); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); float host_data[32]; out.download((JtJJtrSE3 *)&host_data[0]); int shift = 0; for (int i = 0; i < 6; ++i) { for (int j = i; j < 7; ++j) { float value = host_data[shift++]; if (j == 6) vectorB_host[i] = value; else matrixA_host[j * 6 + i] = matrixA_host[i * 6 + j] = value; } } } __inline__ __device__ int2 warpReduceSum(int2 val) { for(int offset = warpSize / 2; offset > 0; offset /= 2) { val.x += __shfl_down(val.x, offset); val.y += __shfl_down(val.y, offset); } return val; } __inline__ __device__ int2 blockReduceSum(int2 val) { static __shared__ int2 shared[32]; int lane = threadIdx.x % warpSize; int wid = threadIdx.x / warpSize; val = warpReduceSum(val); //write reduced value to shared memory if(lane == 0) { shared[wid] = val; } __syncthreads(); const int2 zero = {0, 0}; //ensure we only grab a value from shared memory if that warp existed val = (threadIdx.x < blockDim.x / warpSize) ? shared[lane] : zero; if(wid == 0) { val = warpReduceSum(val); } return val; } __global__ void reduceSum(int2 * in, int2 * out, int N) { int2 sum = {0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { sum.x += in[i].x; sum.y += in[i].y; } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } struct RGBResidual { float minScale; PtrStepSz dIdx; PtrStepSz dIdy; PtrStepSz lastDepth; PtrStepSz nextDepth; PtrStepSz lastImage; PtrStepSz nextImage; mutable PtrStepSz corresImg; float maxDepthDelta; float3 kt; mat33 krkinv; int cols; int rows; int N; int pitch; int imgPitch; int2 * out; __device__ __forceinline__ int2 getProducts(int k) const { int i = k / cols; int j0 = k - (i * cols); int2 value = {0, 0}; DataTerm corres; corres.valid = false; if(i >= 0 && i < rows && j0 >= 0 && j0 < cols) { if(j0 < cols - 5 && i < rows - 1) { bool valid = true; for(int u = max(i - 2, 0); u < min(i + 2, rows); u++) { for(int v = max(j0 - 2, 0); v < min(j0 + 2, cols); v++) { valid = valid && (nextImage.ptr(u)[v] > 0); } } if(valid) { short * ptr_input_x = (short*) ((unsigned char*) dIdx.data + i * pitch); short * ptr_input_y = (short*) ((unsigned char*) dIdy.data + i * pitch); short valx = ptr_input_x[j0]; short valy = ptr_input_y[j0]; float mTwo = (valx * valx) + (valy * valy); if(mTwo >= minScale) { int y = i; int x = j0; float d1 = nextDepth.ptr(y)[x]; if(!isnan(d1)) { float transformed_d1 = (float)(d1 * (krkinv.data[2].x * x + krkinv.data[2].y * y + krkinv.data[2].z) + kt.z); int u0 = __float2int_rn((d1 * (krkinv.data[0].x * x + krkinv.data[0].y * y + krkinv.data[0].z) + kt.x) / transformed_d1); int v0 = __float2int_rn((d1 * (krkinv.data[1].x * x + krkinv.data[1].y * y + krkinv.data[1].z) + kt.y) / transformed_d1); if(u0 >= 0 && v0 >= 0 && u0 < lastDepth.cols && v0 < lastDepth.rows) { float d0 = lastDepth.ptr(v0)[u0]; if(d0 > 0 && std::abs(transformed_d1 - d0) <= maxDepthDelta && lastImage.ptr(v0)[u0] != 0) { corres.zero.x = u0; corres.zero.y = v0; corres.one.x = x; corres.one.y = y; corres.diff = static_cast(nextImage.ptr(y)[x]) - static_cast(lastImage.ptr(v0)[u0]); corres.valid = true; value.x = 1; value.y = corres.diff * corres.diff; } } } } } } } corresImg.data[k] = corres; return value; } __device__ __forceinline__ void operator () () const { int2 sum = {0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { int2 val = getProducts(i); sum.x += val.x; sum.y += val.y; } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } }; __global__ void residualKernel (const RGBResidual rgb) { rgb(); } void computeRgbResidual(const float & minScale, const DeviceArray2D & dIdx, const DeviceArray2D & dIdy, const DeviceArray2D & lastDepth, const DeviceArray2D & nextDepth, const DeviceArray2D & lastImage, const DeviceArray2D & nextImage, DeviceArray2D & corresImg, DeviceArray & sumResidual, const float maxDepthDelta, const float3 & kt, const mat33 & krkinv, int & sigmaSum, int & count, int threads, int blocks) { int cols = nextImage.cols (); int rows = nextImage.rows (); RGBResidual rgb; rgb.minScale = minScale; rgb.dIdx = dIdx; rgb.dIdy = dIdy; rgb.lastDepth = lastDepth; rgb.nextDepth = nextDepth; rgb.lastImage = lastImage; rgb.nextImage = nextImage; rgb.corresImg = corresImg; rgb.maxDepthDelta = maxDepthDelta; rgb.kt = kt; rgb.krkinv = krkinv; rgb.cols = cols; rgb.rows = rows; rgb.pitch = dIdx.step(); rgb.imgPitch = nextImage.step(); rgb.N = cols * rows; rgb.out = sumResidual; residualKernel<<>>(rgb); int2 out_host = {0, 0}; int2 * out; cudaMalloc(&out, sizeof(int2)); cudaMemcpy(out, &out_host, sizeof(int2), cudaMemcpyHostToDevice); reduceSum<<<1, MAX_THREADS>>>(sumResidual, out, blocks); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); cudaMemcpy(&out_host, out, sizeof(int2), cudaMemcpyDeviceToHost); cudaFree(out); count = out_host.x; sigmaSum = out_host.y; } struct SO3Reduction { PtrStepSz lastImage; PtrStepSz nextImage; mat33 imageBasis; mat33 kinv; mat33 krlr; bool gradCheck; int cols; int rows; int N; JtJJtrSO3 * out; __device__ __forceinline__ float2 getGradient(const PtrStepSz img, int x, int y) const { float2 gradient; float actu = static_cast(img.ptr(y)[x]); float back = static_cast(img.ptr(y)[x - 1]); float fore = static_cast(img.ptr(y)[x + 1]); gradient.x = ((back + actu) / 2.0f) - ((fore + actu) / 2.0f); back = static_cast(img.ptr(y - 1)[x]); fore = static_cast(img.ptr(y + 1)[x]); gradient.y = ((back + actu) / 2.0f) - ((fore + actu) / 2.0f); return gradient; } __device__ __forceinline__ JtJJtrSO3 getProducts(int k) const { int y = k / cols; int x = k - (y * cols); bool found_coresp = false; float3 unwarpedReferencePoint = {x, y, 1.0f}; float3 warpedReferencePoint = imageBasis * unwarpedReferencePoint; int2 warpedReferencePixel = {__float2int_rn(warpedReferencePoint.x / warpedReferencePoint.z), __float2int_rn(warpedReferencePoint.y / warpedReferencePoint.z)}; if(warpedReferencePixel.x >= 1 && warpedReferencePixel.x < cols - 1 && warpedReferencePixel.y >= 1 && warpedReferencePixel.y < rows - 1 && x >= 1 && x < cols - 1 && y >= 1 && y < rows - 1) { found_coresp = true; } float row[4]; row[0] = row[1] = row[2] = row[3] = 0.f; if(found_coresp) { float2 gradNext = getGradient(nextImage, warpedReferencePixel.x, warpedReferencePixel.y); float2 gradLast = getGradient(lastImage, x, y); float gx = (gradNext.x + gradLast.x) / 2.0f; float gy = (gradNext.y + gradLast.y) / 2.0f; float3 point = kinv * unwarpedReferencePoint; float z2 = point.z * point.z; float a = krlr.data[0].x; float b = krlr.data[0].y; float c = krlr.data[0].z; float d = krlr.data[1].x; float e = krlr.data[1].y; float f = krlr.data[1].z; float g = krlr.data[2].x; float h = krlr.data[2].y; float i = krlr.data[2].z; //Aren't jacobians great fun float3 leftProduct = {((point.z * (d * gy + a * gx)) - (gy * g * y) - (gx * g * x)) / z2, ((point.z * (e * gy + b * gx)) - (gy * h * y) - (gx * h * x)) / z2, ((point.z * (f * gy + c * gx)) - (gy * i * y) - (gx * i * x)) / z2}; float3 jacRow = cross(leftProduct, point); row[0] = jacRow.x; row[1] = jacRow.y; row[2] = jacRow.z; row[3] = -(static_cast(nextImage.ptr(warpedReferencePixel.y)[warpedReferencePixel.x]) - static_cast(lastImage.ptr(y)[x])); } JtJJtrSO3 values = {row[0] * row[0], row[0] * row[1], row[0] * row[2], row[0] * row[3], row[1] * row[1], row[1] * row[2], row[1] * row[3], row[2] * row[2], row[2] * row[3], row[3] * row[3], found_coresp}; return values; } __device__ __forceinline__ void operator () () const { JtJJtrSO3 sum = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; for(int i = blockIdx.x * blockDim.x + threadIdx.x; i < N; i += blockDim.x * gridDim.x) { JtJJtrSO3 val = getProducts(i); sum.add(val); } sum = blockReduceSum(sum); if(threadIdx.x == 0) { out[blockIdx.x] = sum; } } }; __global__ void so3Kernel (const SO3Reduction so3) { so3(); } void so3Step(const DeviceArray2D & lastImage, const DeviceArray2D & nextImage, const mat33 & imageBasis, const mat33 & kinv, const mat33 & krlr, DeviceArray & sum, DeviceArray & out, float * matrixA_host, float * vectorB_host, float * residual_host, int threads, int blocks) { int cols = nextImage.cols(); int rows = nextImage.rows(); SO3Reduction so3; so3.lastImage = lastImage; so3.nextImage = nextImage; so3.imageBasis = imageBasis; so3.kinv = kinv; so3.krlr = krlr; so3.cols = cols; so3.rows = rows; so3.N = cols * rows; so3.out = sum; so3Kernel<<>>(so3); reduceSum<<<1, MAX_THREADS>>>(sum, out, blocks); cudaSafeCall(cudaGetLastError()); cudaSafeCall(cudaDeviceSynchronize()); float host_data[11]; out.download((JtJJtrSO3 *)&host_data[0]); int shift = 0; for (int i = 0; i < 3; ++i) { for (int j = i; j < 4; ++j) { float value = host_data[shift++]; if (j == 3) vectorB_host[i] = value; else matrixA_host[j * 3 + i] = matrixA_host[i * 3 + j] = value; } } residual_host[0] = host_data[9]; residual_host[1] = host_data[10]; } ================================================ FILE: obj_pose_est/mapping/Core/src/Cuda/types.cuh ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ #ifndef CUDA_TYPES_CUH_ #define CUDA_TYPES_CUH_ #include #if !defined(__CUDACC__) #include #endif struct mat33 { mat33() {} #if !defined(__CUDACC__) mat33(Eigen::Matrix & e) { memcpy(data, e.data(), sizeof(mat33)); } #endif float3 data[3]; }; struct DataTerm { short2 zero; short2 one; float diff; bool valid; }; struct CameraModel { float fx, fy, cx, cy; CameraModel() : fx(0), fy(0), cx(0), cy(0) {} CameraModel(float fx_, float fy_, float cx_, float cy_) : fx(fx_), fy(fy_), cx(cx_), cy(cy_) {} CameraModel operator()(int level) const { int div = 1 << level; return (CameraModel (fx / div, fy / div, cx / div, cy / div)); } }; struct JtJJtrSE3 { //27 floats for each product (27) float aa, ab, ac, ad, ae, af, ag, bb, bc, bd, be, bf, bg, cc, cd, ce, cf, cg, dd, de, df, dg, ee, ef, eg, ff, fg; //Extra data needed (29) float residual, inliers; __device__ inline void add(const JtJJtrSE3 & a) { aa += a.aa; ab += a.ab; ac += a.ac; ad += a.ad; ae += a.ae; af += a.af; ag += a.ag; bb += a.bb; bc += a.bc; bd += a.bd; be += a.be; bf += a.bf; bg += a.bg; cc += a.cc; cd += a.cd; ce += a.ce; cf += a.cf; cg += a.cg; dd += a.dd; de += a.de; df += a.df; dg += a.dg; ee += a.ee; ef += a.ef; eg += a.eg; ff += a.ff; fg += a.fg; residual += a.residual; inliers += a.inliers; } }; struct JtJJtrSO3 { //9 floats for each product (9) float aa, ab, ac, ad, bb, bc, bd, cc, cd; //Extra data needed (11) float residual, inliers; __device__ inline void add(const JtJJtrSO3 & a) { aa += a.aa; ab += a.ab; ac += a.ac; ad += a.ad; bb += a.bb; bc += a.bc; bd += a.bd; cc += a.cc; cd += a.cd; residual += a.residual; inliers += a.inliers; } }; #endif /* CUDA_TYPES_CUH_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/CudaComputeTargetFlags.cmake ================================================ # # Compute target flags macros by Anatoly Baksheev # # Usage in CmakeLists.txt: # include(CudaComputeTargetFlags.cmake) # APPEND_TARGET_ARCH_FLAGS() #compute flags macros MACRO(CUDA_COMPUTE_TARGET_FLAGS arch_bin arch_ptx cuda_nvcc_target_flags) string(REGEX REPLACE "\\." "" ARCH_BIN_WITHOUT_DOTS "${${arch_bin}}") string(REGEX REPLACE "\\." "" ARCH_PTX_WITHOUT_DOTS "${${arch_ptx}}") set(cuda_computer_target_flags_temp "") # Tell NVCC to add binaries for the specified GPUs string(REGEX MATCHALL "[0-9()]+" ARCH_LIST "${ARCH_BIN_WITHOUT_DOTS}") foreach(ARCH IN LISTS ARCH_LIST) if (ARCH MATCHES "([0-9]+)\\(([0-9]+)\\)") # User explicitly specified PTX for the concrete BIN set(cuda_computer_target_flags_temp ${cuda_computer_target_flags_temp} -gencode arch=compute_${CMAKE_MATCH_2},code=sm_${CMAKE_MATCH_1}) else() # User didn't explicitly specify PTX for the concrete BIN, we assume PTX=BIN set(cuda_computer_target_flags_temp ${cuda_computer_target_flags_temp} -gencode arch=compute_${ARCH},code=sm_${ARCH}) endif() endforeach() # Tell NVCC to add PTX intermediate code for the specified architectures string(REGEX MATCHALL "[0-9]+" ARCH_LIST "${ARCH_PTX_WITHOUT_DOTS}") foreach(ARCH IN LISTS ARCH_LIST) set(cuda_computer_target_flags_temp ${cuda_computer_target_flags_temp} -gencode arch=compute_${ARCH},code=compute_${ARCH}) endforeach() set(${cuda_nvcc_target_flags} ${cuda_computer_target_flags_temp}) ENDMACRO() MACRO(APPEND_TARGET_ARCH_FLAGS) set(cuda_nvcc_target_flags "") CUDA_COMPUTE_TARGET_FLAGS(CUDA_ARCH_BIN CUDA_ARCH_PTX cuda_nvcc_target_flags) if (cuda_nvcc_target_flags) message(STATUS "CUDA NVCC target flags: ${cuda_nvcc_target_flags}") list(APPEND CUDA_NVCC_FLAGS ${cuda_nvcc_target_flags}) endif() ENDMACRO() ================================================ FILE: obj_pose_est/mapping/Core/src/Defines.h ================================================ /* * This file was written for porting ElasticFusion to windows * by Filip Srajer (filip.srajer@inf.ethz.ch). * */ #pragma once #ifndef WIN32 # define EFUSION_API #else # ifdef efusion_EXPORTS # define EFUSION_API __declspec(dllexport) # else # define EFUSION_API __declspec(dllimport) # endif #endif ================================================ FILE: obj_pose_est/mapping/Core/src/Deformation.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "Deformation.h" Deformation::Deformation() : def(4, &pointPool), originalPointPool(0), firstGraphNode(0), sampleProgram(loadProgramGeomFromFile("sample.vert", "sample.geom")), bufferSize(1024), //max nodes basically count(0), vertices(new Eigen::Vector4f[bufferSize]), graphPosePoints(new std::vector), lastDeformTime(0) { //x, y, z and init time memset(&vertices[0], 0, bufferSize); glGenTransformFeedbacks(1, &fid); glGenBuffers(1, &vbo); glBindBuffer(GL_ARRAY_BUFFER, vbo); glBufferData(GL_ARRAY_BUFFER, bufferSize * sizeof(Eigen::Vector4f), &vertices[0], GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); sampleProgram->Bind(); int loc[1] = { glGetVaryingLocationNV(sampleProgram->programId(), "vData"), }; glTransformFeedbackVaryingsNV(sampleProgram->programId(), 1, loc, GL_INTERLEAVED_ATTRIBS); sampleProgram->Unbind(); glGenQueries(1, &countQuery); } Deformation::~Deformation() { delete [] vertices; glDeleteTransformFeedbacks(1, &fid); glDeleteBuffers(1, &vbo); glDeleteQueries(1, &countQuery); delete graphPosePoints; } std::vector & Deformation::getGraph() { return def.getGraph(); } void Deformation::addConstraint(const Constraint & constraint) { constraints.push_back(constraint); } void Deformation::addConstraint(const Eigen::Vector4f & src, const Eigen::Vector4f & target, const uint64_t & srcTime, const uint64_t & targetTime, const bool pinConstraints) { //Add the new constraint constraints.push_back(Constraint(src.head(3), target.head(3), srcTime, targetTime, false)); if(pinConstraints) { constraints.push_back(Constraint(target.head(3), target.head(3), targetTime, targetTime, false, true)); } } bool Deformation::constrain(std::vector & ferns, std::vector & rawGraph, int time, const bool fernMatch, std::vector > & poseGraph, const bool relaxGraph, std::vector * newRelativeCons) { if(def.isInit()) { std::vector times; std::vector poses; std::vector rawPoses; //Deform the set of ferns for(size_t i = 0; i < ferns.size(); i++) { times.push_back(ferns.at(i)->srcTime); poses.push_back(ferns.at(i)->pose); rawPoses.push_back(&ferns.at(i)->pose); } if(fernMatch) { //Also apply to the current full pose graph (this might be silly :D) for(size_t i = 0; i < poseGraph.size(); i++) { times.push_back(poseGraph.at(i).first); poses.push_back(poseGraph.at(i).second); rawPoses.push_back(&poseGraph.at(i).second); } } def.setPosesSeq(×, poses); int originalPointPool = pointPool.size(); //Target to source for(size_t i = 0; i < constraints.size(); i++) { pointPool.push_back(constraints.at(i).src); vertexTimes.push_back(constraints.at(i).srcTime); constraints.at(i).srcPointPoolId = pointPool.size() - 1; if(constraints.at(i).relative) { pointPool.push_back(constraints.at(i).target); vertexTimes.push_back(constraints.at(i).targetTime); constraints.at(i).tarPointPoolId = pointPool.size() - 1; } } def.appendVertices(&vertexTimes, originalPointPool); def.clearConstraints(); for(size_t i = 0; i < constraints.size(); i++) { if(constraints.at(i).relative) { def.addRelativeConstraint(constraints.at(i).srcPointPoolId, constraints.at(i).tarPointPoolId); } else { Eigen::Vector3f targetPoint = constraints.at(i).target; def.addConstraint(constraints.at(i).srcPointPoolId, targetPoint); } } float error = 0; float meanConsError = 0; bool optimised = def.optimiseGraphSparse(error, meanConsError, fernMatch, (fernMatch || relaxGraph) ? 0 : lastDeformTime); bool poseUpdated = false; if(!fernMatch || (fernMatch && optimised && meanConsError < 0.0003 && error < 0.12)) { def.applyGraphToPoses(rawPoses); def.applyGraphToVertices(); if(!fernMatch && newRelativeCons) { newRelativeCons->clear(); //Target to source for(size_t i = 0; i < constraints.size(); i++) { if(!constraints.at(i).relative && !constraints.at(i).pin) { newRelativeCons->push_back(Constraint(pointPool.at(constraints.at(i).srcPointPoolId), constraints.at(i).target, constraints.at(i).srcTime, constraints.at(i).targetTime, true)); } } } std::vector & graphNodes = def.getGraph(); std::vector graphTimes = def.getGraphTimes(); //16 floats per node... rawGraph.resize(graphNodes.size() * 16); for(size_t i = 0; i < graphNodes.size(); i++) { memcpy(&rawGraph.at(i * 16), graphNodes.at(i)->position.data(), sizeof(float) * 3); memcpy(&rawGraph.at(i * 16 + 3), graphNodes.at(i)->rotation.data(), sizeof(float) * 9); memcpy(&rawGraph.at(i * 16 + 12), graphNodes.at(i)->translation.data(), sizeof(float) * 3); rawGraph.at(i * 16 + 15) = (float)graphTimes.at(i); } if(!fernMatch && !relaxGraph) { lastDeformTime = time; } poseUpdated = true; } vertexTimes.resize(originalPointPool); pointPool.resize(originalPointPool); constraints.clear(); return poseUpdated; } return false; } void Deformation::sampleGraphFrom(Deformation & other) { Eigen::Vector4f * otherVerts = other.getVertices(); int sampleRate = 5; if(other.getCount() / sampleRate > def.k) { for(int i = 0; i < other.getCount(); i += sampleRate) { Eigen::Vector3f newPoint = otherVerts[i].head<3>(); graphPosePoints->push_back(newPoint); if(i > 0 && otherVerts[i](3) < graphPoseTimes.back()) { assert(false && "Assumption failed"); } graphPoseTimes.push_back(otherVerts[i](3)); } def.initialiseGraph(graphPosePoints, &graphPoseTimes); graphPoseTimes.clear(); graphPosePoints->clear(); } } void Deformation::sampleGraphModel(const std::pair & model) { sampleProgram->Bind(); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, fid); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbo); glBeginQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN, countQuery); glBeginTransformFeedback(GL_POINTS); glDrawTransformFeedback(GL_POINTS, model.second); glEndTransformFeedback(); glEndQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN); glGetQueryObjectuiv(countQuery, GL_QUERY_RESULT, &count); glDisable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); sampleProgram->Unbind(); glFinish(); if((int)count > def.k) { glBindBuffer(GL_ARRAY_BUFFER, vbo); glGetBufferSubData(GL_ARRAY_BUFFER, 0, sizeof(Eigen::Vector4f) * count, vertices); glBindBuffer(GL_ARRAY_BUFFER, 0); for(size_t i = 0; i < count; i++) { Eigen::Vector3f newPoint = vertices[i].head<3>(); graphPosePoints->push_back(newPoint); if(i > 0 && vertices[i](3) < graphPoseTimes.back()) { assert(false && "Assumption failed"); } graphPoseTimes.push_back(vertices[i](3)); } def.initialiseGraph(graphPosePoints, &graphPoseTimes); graphPoseTimes.clear(); graphPosePoints->clear(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Deformation.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef DEFORMATION_H_ #define DEFORMATION_H_ #include "Utils/DeformationGraph.h" #include "Shaders/Shaders.h" #include "Shaders/Uniform.h" #include "Shaders/Vertex.h" #include "GPUTexture.h" #include "Utils/Resolution.h" #include "Utils/Intrinsics.h" #include "Ferns.h" #include "Defines.h" #include class Deformation { public: Deformation(); virtual ~Deformation(); EFUSION_API std::vector & getGraph(); void getRawGraph(std::vector & graph); void sampleGraphModel(const std::pair & model); void sampleGraphFrom(Deformation & other); class Constraint { public: Constraint(const Eigen::Vector3f & src, const Eigen::Vector3f & target, const uint64_t & srcTime, const uint64_t & targetTime, const bool relative, const bool pin = false) : src(src), target(target), srcTime(srcTime), targetTime(targetTime), relative(relative), pin(pin), srcPointPoolId(-1), tarPointPoolId(-1) {} Eigen::Vector3f src; Eigen::Vector3f target; uint64_t srcTime; uint64_t targetTime; bool relative; bool pin; int srcPointPoolId; int tarPointPoolId; }; void addConstraint(const Eigen::Vector4f & src, const Eigen::Vector4f & target, const uint64_t & srcTime, const uint64_t & targetTime, const bool pinConstraints); void addConstraint(const Constraint & constraint); bool constrain(std::vector & ferns, std::vector & rawGraph, int time, const bool fernMatch, std::vector > & poseGraph, const bool relaxGraph, std::vector * newRelativeCons = 0); Eigen::Vector4f * getVertices() { return vertices; } int getCount() { return int(count); } int getLastDeformTime() { return lastDeformTime; } private: DeformationGraph def; std::vector vertexTimes; std::vector pointPool; int originalPointPool; int firstGraphNode; std::shared_ptr sampleProgram; GLuint vbo; GLuint fid; const int bufferSize; GLuint countQuery; unsigned int count; Eigen::Vector4f * vertices; std::vector > poseGraphPoints; std::vector graphPoseTimes; std::vector * graphPosePoints; std::vector constraints; int lastDeformTime; }; #endif /* DEFORMATION_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/ElasticFusion.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "ElasticFusion.h" ElasticFusion::ElasticFusion(const int timeDelta, const int countThresh, const float errThresh, const float covThresh, const bool closeLoops, const bool iclnuim, const bool reloc, const float photoThresh, const float confidence, const float depthCut, const float icpThresh, const bool fastOdom, const float fernThresh, const bool so3, const bool frameToFrameRGB, const std::string fileName) : frameToModel(Resolution::getInstance().width(), Resolution::getInstance().height(), Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()), modelToModel(Resolution::getInstance().width(), Resolution::getInstance().height(), Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()), ferns(500, depthCut * 1000, photoThresh), saveFilename(fileName), currPose(Eigen::Matrix4f::Identity()), tick(1), timeDelta(timeDelta), icpCountThresh(countThresh), icpErrThresh(errThresh), covThresh(covThresh), deforms(0), fernDeforms(0), consSample(20), resize(Resolution::getInstance().width(), Resolution::getInstance().height(), Resolution::getInstance().width() / consSample, Resolution::getInstance().height() / consSample), imageBuff(Resolution::getInstance().rows() / consSample, Resolution::getInstance().cols() / consSample), consBuff(Resolution::getInstance().rows() / consSample, Resolution::getInstance().cols() / consSample), timesBuff(Resolution::getInstance().rows() / consSample, Resolution::getInstance().cols() / consSample), closeLoops(closeLoops), iclnuim(iclnuim), reloc(reloc), lost(false), lastFrameRecovery(false), trackingCount(0), maxDepthProcessed(20.0f), rgbOnly(false), icpWeight(icpThresh), pyramid(true), fastOdom(fastOdom), confidenceThreshold(confidence), fernThresh(fernThresh), so3(so3), frameToFrameRGB(frameToFrameRGB), depthCutoff(depthCut) { createTextures(); createCompute(); createFeedbackBuffers(); std::string filename = fileName; filename.append(".freiburg"); std::ofstream file; file.open(filename.c_str(), std::fstream::out); file.close(); Stopwatch::getInstance().setCustomSignature(12431231); } ElasticFusion::~ElasticFusion() { if(iclnuim) { savePly(); } //Output deformed pose graph std::string fname = saveFilename; fname.append(".freiburg"); std::ofstream f; f.open(fname.c_str(), std::fstream::out); for(size_t i = 0; i < poseGraph.size(); i++) { std::stringstream strs; if(iclnuim) { strs << std::setprecision(6) << std::fixed << (double)poseLogTimes.at(i) << " "; } else { strs << std::setprecision(6) << std::fixed << (double)poseLogTimes.at(i) / 1000000.0 << " "; } Eigen::Vector3f trans = poseGraph.at(i).second.topRightCorner(3, 1); Eigen::Matrix3f rot = poseGraph.at(i).second.topLeftCorner(3, 3); f << strs.str() << trans(0) << " " << trans(1) << " " << trans(2) << " "; Eigen::Quaternionf currentCameraRotation(rot); f << currentCameraRotation.x() << " " << currentCameraRotation.y() << " " << currentCameraRotation.z() << " " << currentCameraRotation.w() << "\n"; } f.close(); for(std::map::iterator it = textures.begin(); it != textures.end(); ++it) { delete it->second; } textures.clear(); for(std::map::iterator it = computePacks.begin(); it != computePacks.end(); ++it) { delete it->second; } computePacks.clear(); for(std::map::iterator it = feedbackBuffers.begin(); it != feedbackBuffers.end(); ++it) { delete it->second; } feedbackBuffers.clear(); } void ElasticFusion::createTextures() { textures[GPUTexture::RGB] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, true, true); textures[GPUTexture::DEPTH_RAW] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE16UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT); textures[GPUTexture::DEPTH_FILTERED] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE16UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT, false, true); textures[GPUTexture::DEPTH_METRIC] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE32F_ARB, GL_LUMINANCE, GL_FLOAT); textures[GPUTexture::DEPTH_METRIC_FILTERED] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE32F_ARB, GL_LUMINANCE, GL_FLOAT); textures[GPUTexture::DEPTH_NORM] = new GPUTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE, GL_LUMINANCE, GL_FLOAT, true); } void ElasticFusion::createCompute() { computePacks[ComputePack::NORM] = new ComputePack(loadProgramFromFile("empty.vert", "depth_norm.frag", "quad.geom"), textures[GPUTexture::DEPTH_NORM]->texture); computePacks[ComputePack::FILTER] = new ComputePack(loadProgramFromFile("empty.vert", "depth_bilateral.frag", "quad.geom"), textures[GPUTexture::DEPTH_FILTERED]->texture); computePacks[ComputePack::METRIC] = new ComputePack(loadProgramFromFile("empty.vert", "depth_metric.frag", "quad.geom"), textures[GPUTexture::DEPTH_METRIC]->texture); computePacks[ComputePack::METRIC_FILTERED] = new ComputePack(loadProgramFromFile("empty.vert", "depth_metric.frag", "quad.geom"), textures[GPUTexture::DEPTH_METRIC_FILTERED]->texture); } void ElasticFusion::createFeedbackBuffers() { feedbackBuffers[FeedbackBuffer::RAW] = new FeedbackBuffer(loadProgramGeomFromFile("vertex_feedback.vert", "vertex_feedback.geom")); feedbackBuffers[FeedbackBuffer::FILTERED] = new FeedbackBuffer(loadProgramGeomFromFile("vertex_feedback.vert", "vertex_feedback.geom")); } void ElasticFusion::computeFeedbackBuffers() { TICK("feedbackBuffers"); feedbackBuffers[FeedbackBuffer::RAW]->compute(textures[GPUTexture::RGB]->texture, textures[GPUTexture::DEPTH_METRIC]->texture, tick, maxDepthProcessed); feedbackBuffers[FeedbackBuffer::FILTERED]->compute(textures[GPUTexture::RGB]->texture, textures[GPUTexture::DEPTH_METRIC_FILTERED]->texture, tick, maxDepthProcessed); TOCK("feedbackBuffers"); } bool ElasticFusion::denseEnough(const Img> & img) { int sum = 0; for(int i = 0; i < img.rows; i++) { for(int j = 0; j < img.cols; j++) { sum += img.at>(i, j)(0) > 0 && img.at>(i, j)(1) > 0 && img.at>(i, j)(2) > 0; } } return float(sum) / float(img.rows * img.cols) > 0.75f; } void ElasticFusion::processFrame(const unsigned char * rgb, const unsigned short * depth, const int64_t & timestamp, const Eigen::Matrix4f * inPose, const float weightMultiplier, const bool bootstrap) { TICK("Run"); textures[GPUTexture::DEPTH_RAW]->texture->Upload(depth, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT); textures[GPUTexture::RGB]->texture->Upload(rgb, GL_RGB, GL_UNSIGNED_BYTE); TICK("Preprocess"); filterDepth(); metriciseDepth(); TOCK("Preprocess"); //First run if(tick == 1) { computeFeedbackBuffers(); globalModel.initialise(*feedbackBuffers[FeedbackBuffer::RAW], *feedbackBuffers[FeedbackBuffer::FILTERED]); frameToModel.initFirstRGB(textures[GPUTexture::RGB]); } else { Eigen::Matrix4f lastPose = currPose; bool trackingOk = true; if(bootstrap || !inPose) { TICK("autoFill"); resize.image(indexMap.imageTex(), imageBuff); bool shouldFillIn = !denseEnough(imageBuff); TOCK("autoFill"); TICK("odomInit"); //WARNING initICP* must be called before initRGB* frameToModel.initICPModel(shouldFillIn ? &fillIn.vertexTexture : indexMap.vertexTex(), shouldFillIn ? &fillIn.normalTexture : indexMap.normalTex(), maxDepthProcessed, currPose); frameToModel.initRGBModel((shouldFillIn || frameToFrameRGB) ? &fillIn.imageTexture : indexMap.imageTex()); frameToModel.initICP(textures[GPUTexture::DEPTH_FILTERED], maxDepthProcessed); frameToModel.initRGB(textures[GPUTexture::RGB]); TOCK("odomInit"); if(bootstrap) { assert(inPose); currPose = currPose * (*inPose); } Eigen::Vector3f trans = currPose.topRightCorner(3, 1); Eigen::Matrix rot = currPose.topLeftCorner(3, 3); TICK("odom"); frameToModel.getIncrementalTransformation(trans, rot, rgbOnly, icpWeight, pyramid, fastOdom, so3); TOCK("odom"); trackingOk = !reloc || frameToModel.lastICPError < 1e-04; if(reloc) { if(!lost) { Eigen::MatrixXd covariance = frameToModel.getCovariance(); for(int i = 0; i < 6; i++) { if(covariance(i, i) > 1e-04) { trackingOk = false; break; } } if(!trackingOk) { trackingCount++; if(trackingCount > 10) { lost = true; } } else { trackingCount = 0; } } else if(lastFrameRecovery) { Eigen::MatrixXd covariance = frameToModel.getCovariance(); for(int i = 0; i < 6; i++) { if(covariance(i, i) > 1e-04) { trackingOk = false; break; } } if(trackingOk) { lost = false; trackingCount = 0; } lastFrameRecovery = false; } } currPose.topRightCorner(3, 1) = trans; currPose.topLeftCorner(3, 3) = rot; } else { currPose = *inPose; } //std::cout << trackingOk << " " << lost << " " << trackingCount << " " << lastFrameRecovery << "\n"; Eigen::Matrix4f diff = currPose.inverse() * lastPose; Eigen::Vector3f diffTrans = diff.topRightCorner(3, 1); Eigen::Matrix3f diffRot = diff.topLeftCorner(3, 3); //Weight by velocity float weighting = std::max(diffTrans.norm(), rodrigues2(diffRot).norm()); float largest = 0.01; float minWeight = 0.5; if(weighting > largest) { weighting = largest; } weighting = std::max(1.0f - (weighting / largest), minWeight) * weightMultiplier; std::vector constraints; predict(); Eigen::Matrix4f recoveryPose = currPose; if(closeLoops) { lastFrameRecovery = false; TICK("Ferns::findFrame"); recoveryPose = ferns.findFrame(constraints, currPose, &fillIn.vertexTexture, &fillIn.normalTexture, &fillIn.imageTexture, tick, lost); TOCK("Ferns::findFrame"); } std::vector rawGraph; bool fernAccepted = false; if(closeLoops && ferns.lastClosest != -1) { if(lost) { currPose = recoveryPose; lastFrameRecovery = true; } else { for(size_t i = 0; i < constraints.size(); i++) { globalDeformation.addConstraint(constraints.at(i).sourcePoint, constraints.at(i).targetPoint, tick, ferns.frames.at(ferns.lastClosest)->srcTime, true); } for(size_t i = 0; i < relativeCons.size(); i++) { globalDeformation.addConstraint(relativeCons.at(i)); } if(globalDeformation.constrain(ferns.frames, rawGraph, tick, true, poseGraph, true)) { currPose = recoveryPose; poseMatches.push_back(PoseMatch(ferns.lastClosest, ferns.frames.size(), ferns.frames.at(ferns.lastClosest)->pose, currPose, constraints, true)); fernDeforms += rawGraph.size() > 0; fernAccepted = true; } } } //If we didn't match to a fern if(!lost && closeLoops && rawGraph.size() == 0) { //Only predict old view, since we just predicted the current view for the ferns (which failed!) TICK("IndexMap::INACTIVE"); indexMap.combinedPredict(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, 0, tick - timeDelta, timeDelta, IndexMap::INACTIVE); TOCK("IndexMap::INACTIVE"); //WARNING initICP* must be called before initRGB* modelToModel.initICPModel(indexMap.oldVertexTex(), indexMap.oldNormalTex(), maxDepthProcessed, currPose); modelToModel.initRGBModel(indexMap.oldImageTex()); modelToModel.initICP(indexMap.vertexTex(), indexMap.normalTex(), maxDepthProcessed); modelToModel.initRGB(indexMap.imageTex()); Eigen::Vector3f trans = currPose.topRightCorner(3, 1); Eigen::Matrix rot = currPose.topLeftCorner(3, 3); modelToModel.getIncrementalTransformation(trans, rot, false, 10, pyramid, fastOdom, false); Eigen::MatrixXd covar = modelToModel.getCovariance(); bool covOk = true; for(int i = 0; i < 6; i++) { if(covar(i, i) > covThresh) { covOk = false; break; } } Eigen::Matrix4f estPose = Eigen::Matrix4f::Identity(); estPose.topRightCorner(3, 1) = trans; estPose.topLeftCorner(3, 3) = rot; if(covOk && modelToModel.lastICPCount > icpCountThresh && modelToModel.lastICPError < icpErrThresh) { resize.vertex(indexMap.vertexTex(), consBuff); resize.time(indexMap.oldTimeTex(), timesBuff); for(int i = 0; i < consBuff.cols; i++) { for(int j = 0; j < consBuff.rows; j++) { if(consBuff.at(j, i)(2) > 0 && consBuff.at(j, i)(2) < maxDepthProcessed && timesBuff.at(j, i) > 0) { Eigen::Vector4f worldRawPoint = currPose * Eigen::Vector4f(consBuff.at(j, i)(0), consBuff.at(j, i)(1), consBuff.at(j, i)(2), 1.0f); Eigen::Vector4f worldModelPoint = estPose * Eigen::Vector4f(consBuff.at(j, i)(0), consBuff.at(j, i)(1), consBuff.at(j, i)(2), 1.0f); constraints.push_back(Ferns::SurfaceConstraint(worldRawPoint, worldModelPoint)); localDeformation.addConstraint(worldRawPoint, worldModelPoint, tick, timesBuff.at(j, i), deforms == 0); } } } std::vector newRelativeCons; if(localDeformation.constrain(ferns.frames, rawGraph, tick, false, poseGraph, false, &newRelativeCons)) { poseMatches.push_back(PoseMatch(ferns.frames.size() - 1, ferns.frames.size(), estPose, currPose, constraints, false)); deforms += rawGraph.size() > 0; currPose = estPose; for(size_t i = 0; i < newRelativeCons.size(); i += newRelativeCons.size() / 3) { relativeCons.push_back(newRelativeCons.at(i)); } } } } if(!rgbOnly && trackingOk && !lost) { TICK("indexMap"); indexMap.predictIndices(currPose, tick, globalModel.model(), maxDepthProcessed, timeDelta); TOCK("indexMap"); globalModel.fuse(currPose, tick, textures[GPUTexture::RGB], textures[GPUTexture::DEPTH_METRIC], textures[GPUTexture::DEPTH_METRIC_FILTERED], indexMap.indexTex(), indexMap.vertConfTex(), indexMap.colorTimeTex(), indexMap.normalRadTex(), maxDepthProcessed, confidenceThreshold, weighting); TICK("indexMap"); indexMap.predictIndices(currPose, tick, globalModel.model(), maxDepthProcessed, timeDelta); TOCK("indexMap"); //If we're deforming we need to predict the depth again to figure out which //points to update the timestamp's of, since a deformation means a second pose update //this loop if(rawGraph.size() > 0 && !fernAccepted) { indexMap.synthesizeDepth(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, tick, tick - timeDelta, std::numeric_limits::max()); } globalModel.clean(currPose, tick, indexMap.indexTex(), indexMap.vertConfTex(), indexMap.colorTimeTex(), indexMap.normalRadTex(), indexMap.depthTex(), confidenceThreshold, rawGraph, timeDelta, maxDepthProcessed, fernAccepted); } } poseGraph.push_back(std::pair(tick, currPose)); poseLogTimes.push_back(timestamp); TICK("sampleGraph"); localDeformation.sampleGraphModel(globalModel.model()); globalDeformation.sampleGraphFrom(localDeformation); TOCK("sampleGraph"); predict(); if(!lost) { processFerns(); tick++; } TOCK("Run"); } void ElasticFusion::processFrame_withseg(const unsigned char * rgb, const unsigned short * depth, const unsigned short * seg, const float weight_rgb, const float weight_seg, const int64_t & timestamp, const Eigen::Matrix4f * inPose, const float weightMultiplier, const bool bootstrap) { TICK("Run"); textures[GPUTexture::DEPTH_RAW]->texture->Upload(depth, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT); textures[GPUTexture::RGB]->texture->Upload(rgb, GL_RGB, GL_UNSIGNED_BYTE); TICK("Preprocess"); filterDepth(); metriciseDepth(); TOCK("Preprocess"); //First run if(tick == 1) { computeFeedbackBuffers(); globalModel.initialise(*feedbackBuffers[FeedbackBuffer::RAW], *feedbackBuffers[FeedbackBuffer::FILTERED]); frameToModel.initFirstRGB(textures[GPUTexture::RGB]); } else { Eigen::Matrix4f lastPose = currPose; bool trackingOk = true; if(bootstrap || !inPose) { TICK("autoFill"); resize.image(indexMap.imageTex(), imageBuff); bool shouldFillIn = !denseEnough(imageBuff); TOCK("autoFill"); TICK("odomInit"); //WARNING initICP* must be called before initRGB* frameToModel.initICPModel(shouldFillIn ? &fillIn.vertexTexture : indexMap.vertexTex(), shouldFillIn ? &fillIn.normalTexture : indexMap.normalTex(), maxDepthProcessed, currPose); frameToModel.initRGBModel((shouldFillIn || frameToFrameRGB) ? &fillIn.imageTexture : indexMap.imageTex()); frameToModel.initICP(textures[GPUTexture::DEPTH_FILTERED], maxDepthProcessed); frameToModel.initRGB(textures[GPUTexture::RGB]); TOCK("odomInit"); if(bootstrap) { assert(inPose); currPose = currPose * (*inPose); } Eigen::Vector3f trans = currPose.topRightCorner(3, 1); Eigen::Matrix rot = currPose.topLeftCorner(3, 3); TICK("odom"); frameToModel.getIncrementalTransformation_withseg(trans, rot, rgbOnly, weight_rgb, weight_seg, icpWeight, pyramid, fastOdom, so3); TOCK("odom"); trackingOk = !reloc || frameToModel.lastICPError < 1e-04; if(reloc) { if(!lost) { Eigen::MatrixXd covariance = frameToModel.getCovariance(); for(int i = 0; i < 6; i++) { if(covariance(i, i) > 1e-04) { trackingOk = false; break; } } if(!trackingOk) { trackingCount++; if(trackingCount > 10) { lost = true; } } else { trackingCount = 0; } } else if(lastFrameRecovery) { Eigen::MatrixXd covariance = frameToModel.getCovariance(); for(int i = 0; i < 6; i++) { if(covariance(i, i) > 1e-04) { trackingOk = false; break; } } if(trackingOk) { lost = false; trackingCount = 0; } lastFrameRecovery = false; } } currPose.topRightCorner(3, 1) = trans; currPose.topLeftCorner(3, 3) = rot; } else { currPose = *inPose; } //std::cout << trackingOk << " " << lost << " " << trackingCount << " " << lastFrameRecovery << "\n"; Eigen::Matrix4f diff = currPose.inverse() * lastPose; Eigen::Vector3f diffTrans = diff.topRightCorner(3, 1); Eigen::Matrix3f diffRot = diff.topLeftCorner(3, 3); //Weight by velocity float weighting = std::max(diffTrans.norm(), rodrigues2(diffRot).norm()); float largest = 0.01; float minWeight = 0.5; if(weighting > largest) { weighting = largest; } weighting = std::max(1.0f - (weighting / largest), minWeight) * weightMultiplier; std::vector constraints; predict(); Eigen::Matrix4f recoveryPose = currPose; if(closeLoops) { lastFrameRecovery = false; TICK("Ferns::findFrame"); recoveryPose = ferns.findFrame(constraints, currPose, &fillIn.vertexTexture, &fillIn.normalTexture, &fillIn.imageTexture, tick, lost); TOCK("Ferns::findFrame"); } std::vector rawGraph; bool fernAccepted = false; if(closeLoops && ferns.lastClosest != -1) { if(lost) { currPose = recoveryPose; lastFrameRecovery = true; } else { for(size_t i = 0; i < constraints.size(); i++) { globalDeformation.addConstraint(constraints.at(i).sourcePoint, constraints.at(i).targetPoint, tick, ferns.frames.at(ferns.lastClosest)->srcTime, true); } for(size_t i = 0; i < relativeCons.size(); i++) { globalDeformation.addConstraint(relativeCons.at(i)); } if(globalDeformation.constrain(ferns.frames, rawGraph, tick, true, poseGraph, true)) { currPose = recoveryPose; poseMatches.push_back(PoseMatch(ferns.lastClosest, ferns.frames.size(), ferns.frames.at(ferns.lastClosest)->pose, currPose, constraints, true)); fernDeforms += rawGraph.size() > 0; fernAccepted = true; } } } //If we didn't match to a fern if(!lost && closeLoops && rawGraph.size() == 0) { //Only predict old view, since we just predicted the current view for the ferns (which failed!) TICK("IndexMap::INACTIVE"); indexMap.combinedPredict(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, 0, tick - timeDelta, timeDelta, IndexMap::INACTIVE); TOCK("IndexMap::INACTIVE"); //WARNING initICP* must be called before initRGB* modelToModel.initICPModel(indexMap.oldVertexTex(), indexMap.oldNormalTex(), maxDepthProcessed, currPose); modelToModel.initRGBModel(indexMap.oldImageTex()); modelToModel.initICP(indexMap.vertexTex(), indexMap.normalTex(), maxDepthProcessed); modelToModel.initRGB(indexMap.imageTex()); Eigen::Vector3f trans = currPose.topRightCorner(3, 1); Eigen::Matrix rot = currPose.topLeftCorner(3, 3); modelToModel.getIncrementalTransformation(trans, rot, false, 10, pyramid, fastOdom, false); Eigen::MatrixXd covar = modelToModel.getCovariance(); bool covOk = true; for(int i = 0; i < 6; i++) { if(covar(i, i) > covThresh) { covOk = false; break; } } Eigen::Matrix4f estPose = Eigen::Matrix4f::Identity(); estPose.topRightCorner(3, 1) = trans; estPose.topLeftCorner(3, 3) = rot; if(covOk && modelToModel.lastICPCount > icpCountThresh && modelToModel.lastICPError < icpErrThresh) { resize.vertex(indexMap.vertexTex(), consBuff); resize.time(indexMap.oldTimeTex(), timesBuff); for(int i = 0; i < consBuff.cols; i++) { for(int j = 0; j < consBuff.rows; j++) { if(consBuff.at(j, i)(2) > 0 && consBuff.at(j, i)(2) < maxDepthProcessed && timesBuff.at(j, i) > 0) { Eigen::Vector4f worldRawPoint = currPose * Eigen::Vector4f(consBuff.at(j, i)(0), consBuff.at(j, i)(1), consBuff.at(j, i)(2), 1.0f); Eigen::Vector4f worldModelPoint = estPose * Eigen::Vector4f(consBuff.at(j, i)(0), consBuff.at(j, i)(1), consBuff.at(j, i)(2), 1.0f); constraints.push_back(Ferns::SurfaceConstraint(worldRawPoint, worldModelPoint)); localDeformation.addConstraint(worldRawPoint, worldModelPoint, tick, timesBuff.at(j, i), deforms == 0); } } } std::vector newRelativeCons; if(localDeformation.constrain(ferns.frames, rawGraph, tick, false, poseGraph, false, &newRelativeCons)) { poseMatches.push_back(PoseMatch(ferns.frames.size() - 1, ferns.frames.size(), estPose, currPose, constraints, false)); deforms += rawGraph.size() > 0; currPose = estPose; for(size_t i = 0; i < newRelativeCons.size(); i += newRelativeCons.size() / 3) { relativeCons.push_back(newRelativeCons.at(i)); } } } } if(!rgbOnly && trackingOk && !lost) { TICK("indexMap"); indexMap.predictIndices(currPose, tick, globalModel.model(), maxDepthProcessed, timeDelta); TOCK("indexMap"); globalModel.fuse(currPose, tick, textures[GPUTexture::RGB], textures[GPUTexture::DEPTH_METRIC], textures[GPUTexture::DEPTH_METRIC_FILTERED], indexMap.indexTex(), indexMap.vertConfTex(), indexMap.colorTimeTex(), indexMap.normalRadTex(), maxDepthProcessed, confidenceThreshold, weighting); TICK("indexMap"); indexMap.predictIndices(currPose, tick, globalModel.model(), maxDepthProcessed, timeDelta); TOCK("indexMap"); //If we're deforming we need to predict the depth again to figure out which //points to update the timestamp's of, since a deformation means a second pose update //this loop if(rawGraph.size() > 0 && !fernAccepted) { indexMap.synthesizeDepth(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, tick, tick - timeDelta, std::numeric_limits::max()); } globalModel.clean(currPose, tick, indexMap.indexTex(), indexMap.vertConfTex(), indexMap.colorTimeTex(), indexMap.normalRadTex(), indexMap.depthTex(), confidenceThreshold, rawGraph, timeDelta, maxDepthProcessed, fernAccepted); } } poseGraph.push_back(std::pair(tick, currPose)); poseLogTimes.push_back(timestamp); TICK("sampleGraph"); localDeformation.sampleGraphModel(globalModel.model()); globalDeformation.sampleGraphFrom(localDeformation); TOCK("sampleGraph"); predict(); if(!lost) { processFerns(); tick++; } TOCK("Run"); } void ElasticFusion::processFerns() { TICK("Ferns::addFrame"); ferns.addFrame(&fillIn.imageTexture, &fillIn.vertexTexture, &fillIn.normalTexture, currPose, tick, fernThresh); TOCK("Ferns::addFrame"); } void ElasticFusion::predict() { TICK("IndexMap::ACTIVE"); if(lastFrameRecovery) { indexMap.combinedPredict(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, 0, tick, timeDelta, IndexMap::ACTIVE); } else { indexMap.combinedPredict(currPose, globalModel.model(), maxDepthProcessed, confidenceThreshold, tick, tick, timeDelta, IndexMap::ACTIVE); } TICK("FillIn"); fillIn.vertex(indexMap.vertexTex(), textures[GPUTexture::DEPTH_FILTERED], lost); fillIn.normal(indexMap.normalTex(), textures[GPUTexture::DEPTH_FILTERED], lost); fillIn.image(indexMap.imageTex(), textures[GPUTexture::RGB], lost || frameToFrameRGB); TOCK("FillIn"); TOCK("IndexMap::ACTIVE"); } void ElasticFusion::metriciseDepth() { std::vector uniforms; uniforms.push_back(Uniform("maxD", depthCutoff)); computePacks[ComputePack::METRIC]->compute(textures[GPUTexture::DEPTH_RAW]->texture, &uniforms); computePacks[ComputePack::METRIC_FILTERED]->compute(textures[GPUTexture::DEPTH_FILTERED]->texture, &uniforms); } void ElasticFusion::filterDepth() { std::vector uniforms; uniforms.push_back(Uniform("cols", (float)Resolution::getInstance().cols())); uniforms.push_back(Uniform("rows", (float)Resolution::getInstance().rows())); uniforms.push_back(Uniform("maxD", depthCutoff)); computePacks[ComputePack::FILTER]->compute(textures[GPUTexture::DEPTH_RAW]->texture, &uniforms); } void ElasticFusion::normaliseDepth(const float & minVal, const float & maxVal) { std::vector uniforms; uniforms.push_back(Uniform("maxVal", maxVal * 1000.f)); uniforms.push_back(Uniform("minVal", minVal * 1000.f)); computePacks[ComputePack::NORM]->compute(textures[GPUTexture::DEPTH_RAW]->texture, &uniforms); } void ElasticFusion::savePly() { std::string filename = saveFilename; filename.append(".ply"); // Open file std::ofstream fs; fs.open (filename.c_str ()); Eigen::Vector4f * mapData = globalModel.downloadMap(); int validCount = 0; for(unsigned int i = 0; i < globalModel.lastCount(); i++) { Eigen::Vector4f pos = mapData[(i * 3) + 0]; if(pos[3] > confidenceThreshold) { validCount++; } } // Write header fs << "ply"; fs << "\nformat " << "binary_little_endian" << " 1.0"; // Vertices fs << "\nelement vertex "<< validCount; fs << "\nproperty float x" "\nproperty float y" "\nproperty float z"; fs << "\nproperty uchar red" "\nproperty uchar green" "\nproperty uchar blue"; fs << "\nproperty float nx" "\nproperty float ny" "\nproperty float nz"; fs << "\nproperty float radius"; fs << "\nend_header\n"; // Close the file fs.close (); // Open file in binary appendable std::ofstream fpout (filename.c_str (), std::ios::app | std::ios::binary); for(unsigned int i = 0; i < globalModel.lastCount(); i++) { Eigen::Vector4f pos = mapData[(i * 3) + 0]; if(pos[3] > confidenceThreshold) { Eigen::Vector4f col = mapData[(i * 3) + 1]; Eigen::Vector4f nor = mapData[(i * 3) + 2]; nor[0] *= -1; nor[1] *= -1; nor[2] *= -1; float value; memcpy (&value, &pos[0], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); memcpy (&value, &pos[1], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); memcpy (&value, &pos[2], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); unsigned char r = int(col[0]) >> 16 & 0xFF; unsigned char g = int(col[0]) >> 8 & 0xFF; unsigned char b = int(col[0]) & 0xFF; fpout.write (reinterpret_cast (&r), sizeof (unsigned char)); fpout.write (reinterpret_cast (&g), sizeof (unsigned char)); fpout.write (reinterpret_cast (&b), sizeof (unsigned char)); memcpy (&value, &nor[0], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); memcpy (&value, &nor[1], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); memcpy (&value, &nor[2], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); memcpy (&value, &nor[3], sizeof (float)); fpout.write (reinterpret_cast (&value), sizeof (float)); } } // Close file fs.close (); delete [] mapData; } Eigen::Vector3f ElasticFusion::rodrigues2(const Eigen::Matrix3f& matrix) { Eigen::JacobiSVD svd(matrix, Eigen::ComputeFullV | Eigen::ComputeFullU); Eigen::Matrix3f R = svd.matrixU() * svd.matrixV().transpose(); double rx = R(2, 1) - R(1, 2); double ry = R(0, 2) - R(2, 0); double rz = R(1, 0) - R(0, 1); double s = sqrt((rx*rx + ry*ry + rz*rz)*0.25); double c = (R.trace() - 1) * 0.5; c = c > 1. ? 1. : c < -1. ? -1. : c; double theta = acos(c); if( s < 1e-5 ) { double t; if( c > 0 ) rx = ry = rz = 0; else { t = (R(0, 0) + 1)*0.5; rx = sqrt( std::max(t, 0.0) ); t = (R(1, 1) + 1)*0.5; ry = sqrt( std::max(t, 0.0) ) * (R(0, 1) < 0 ? -1.0 : 1.0); t = (R(2, 2) + 1)*0.5; rz = sqrt( std::max(t, 0.0) ) * (R(0, 2) < 0 ? -1.0 : 1.0); if( fabs(rx) < fabs(ry) && fabs(rx) < fabs(rz) && (R(1, 2) > 0) != (ry*rz > 0) ) rz = -rz; theta /= sqrt(rx*rx + ry*ry + rz*rz); rx *= theta; ry *= theta; rz *= theta; } } else { double vth = 1/(2*s); vth *= theta; rx *= vth; ry *= vth; rz *= vth; } return Eigen::Vector3d(rx, ry, rz).cast(); } //Sad times ahead IndexMap & ElasticFusion::getIndexMap() { return indexMap; } GlobalModel & ElasticFusion::getGlobalModel() { return globalModel; } Ferns & ElasticFusion::getFerns() { return ferns; } Deformation & ElasticFusion::getLocalDeformation() { return localDeformation; } std::map & ElasticFusion::getTextures() { return textures; } const std::vector & ElasticFusion::getPoseMatches() { return poseMatches; } const RGBDOdometry & ElasticFusion::getModelToModel() { return modelToModel; } const float & ElasticFusion::getConfidenceThreshold() { return confidenceThreshold; } void ElasticFusion::setRgbOnly(const bool & val) { rgbOnly = val; } void ElasticFusion::setIcpWeight(const float & val) { icpWeight = val; } void ElasticFusion::setPyramid(const bool & val) { pyramid = val; } void ElasticFusion::setFastOdom(const bool & val) { fastOdom = val; } void ElasticFusion::setSo3(const bool & val) { so3 = val; } void ElasticFusion::setFrameToFrameRGB(const bool & val) { frameToFrameRGB = val; } void ElasticFusion::setConfidenceThreshold(const float & val) { confidenceThreshold = val; } void ElasticFusion::setFernThresh(const float & val) { fernThresh = val; } void ElasticFusion::setDepthCutoff(const float & val) { depthCutoff = val; } const bool & ElasticFusion::getLost() //lel { return lost; } const int & ElasticFusion::getTick() { return tick; } const int & ElasticFusion::getTimeDelta() { return timeDelta; } void ElasticFusion::setTick(const int & val) { tick = val; } const float & ElasticFusion::getMaxDepthProcessed() { return maxDepthProcessed; } const Eigen::Matrix4f & ElasticFusion::getCurrPose() { return currPose; } const int & ElasticFusion::getDeforms() { return deforms; } const int & ElasticFusion::getFernDeforms() { return fernDeforms; } std::map & ElasticFusion::getFeedbackBuffers() { return feedbackBuffers; } ================================================ FILE: obj_pose_est/mapping/Core/src/ElasticFusion.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef ELASTICFUSION_H_ #define ELASTICFUSION_H_ #include "Utils/RGBDOdometry.h" #include "Utils/Resolution.h" #include "Utils/Intrinsics.h" #include "Utils/Stopwatch.h" #include "Shaders/Shaders.h" #include "Shaders/ComputePack.h" #include "Shaders/FeedbackBuffer.h" #include "Shaders/FillIn.h" #include "Deformation.h" #include "GlobalModel.h" #include "IndexMap.h" #include "Ferns.h" #include "PoseMatch.h" #include "Defines.h" #include #include class ElasticFusion { public: EFUSION_API ElasticFusion(const int timeDelta = 200, const int countThresh = 35000, const float errThresh = 5e-05, const float covThresh = 1e-05, const bool closeLoops = true, const bool iclnuim = false, const bool reloc = false, const float photoThresh = 115, const float confidence = 10, const float depthCut = 3, const float icpThresh = 10, const bool fastOdom = false, const float fernThresh = 0.3095, const bool so3 = true, const bool frameToFrameRGB = false, const std::string fileName = ""); virtual ~ElasticFusion(); /** * Process an rgb/depth map pair * @param rgb unsigned char row major order * @param depth unsigned short z-depth in millimeters, invalid depths are 0 * @param timestamp nanoseconds (actually only used for the output poses, not important otherwise) * @param inPose optional input SE3 pose (if provided, we don't attempt to perform tracking) * @param weightMultiplier optional full frame fusion weight * @param bootstrap if true, use inPose as a pose guess rather than replacement */ EFUSION_API void processFrame(const unsigned char * rgb, const unsigned short * depth, const int64_t & timestamp, const Eigen::Matrix4f * inPose = 0, const float weightMultiplier = 1.f, const bool bootstrap = false); EFUSION_API void processFrame_withseg(const unsigned char * rgb, const unsigned short * depth, const unsigned short * seg, const float weight_rgb, const float weight_seg, const int64_t & timestamp, const Eigen::Matrix4f * inPose = 0, const float weightMultiplier = 1.f, const bool bootstrap = false); /** * Predicts the current view of the scene, updates the [vertex/normal/image]Tex() members * of the indexMap class */ EFUSION_API void predict(); /** * This class contains all of the predicted renders * @return reference */ EFUSION_API IndexMap & getIndexMap(); /** * This class contains the surfel map * @return */ EFUSION_API GlobalModel & getGlobalModel(); /** * This class contains the fern keyframe database * @return */ EFUSION_API Ferns & getFerns(); /** * This class contains the local deformation graph * @return */ EFUSION_API Deformation & getLocalDeformation(); /** * This is the map of raw input textures (you can display these) * @return */ EFUSION_API std::map & getTextures(); /** * This is the list of deformation constraints * @return */ EFUSION_API const std::vector & getPoseMatches(); /** * This is the tracking class, if you want access * @return */ EFUSION_API const RGBDOdometry & getModelToModel(); /** * The point fusion confidence threshold * @return */ EFUSION_API const float & getConfidenceThreshold(); /** * If you set this to true we just do 2.5D RGB-only Lucas–Kanade tracking (no fusion) * @param val */ EFUSION_API void setRgbOnly(const bool & val); /** * Weight for ICP in tracking * @param val if 100, only use depth for tracking, if 0, only use RGB. Best value is 10 */ EFUSION_API void setIcpWeight(const float & val); /** * Whether or not to use a pyramid for tracking * @param val default is true */ EFUSION_API void setPyramid(const bool & val); /** * Controls the number of tracking iterations * @param val default is false */ EFUSION_API void setFastOdom(const bool & val); /** * Turns on or off SO(3) alignment bootstrapping * @param val */ EFUSION_API void setSo3(const bool & val); /** * Turns on or off frame to frame tracking for RGB * @param val */ EFUSION_API void setFrameToFrameRGB(const bool & val); /** * Raw data fusion confidence threshold * @param val default value is 10, but you can play around with this */ EFUSION_API void setConfidenceThreshold(const float & val); /** * Threshold for sampling new keyframes * @param val default is some magic value, change at your own risk */ EFUSION_API void setFernThresh(const float & val); /** * Cut raw depth input off at this point * @param val default is 3 meters */ EFUSION_API void setDepthCutoff(const float & val); /** * Returns whether or not the camera is lost, if relocalisation mode is on * @return */ EFUSION_API const bool & getLost(); /** * Get the internal clock value of the fusion process * @return monotonically increasing integer value (not real-world time) */ EFUSION_API const int & getTick(); /** * Get the time window length for model matching * @return */ EFUSION_API const int & getTimeDelta(); /** * Cheat the clock, only useful for multisession/log fast forwarding * @param val control time itself! */ EFUSION_API void setTick(const int & val); /** * Internal maximum depth processed, this is defaulted to 20 (for rescaling depth buffers) * @return */ EFUSION_API const float & getMaxDepthProcessed(); /** * The current global camera pose estimate * @return SE3 pose */ EFUSION_API const Eigen::Matrix4f & getCurrPose(); /** * The number of local deformations that have occurred * @return */ EFUSION_API const int & getDeforms(); /** * The number of global deformations that have occured * @return */ EFUSION_API const int & getFernDeforms(); /** * These are the vertex buffers computed from the raw input data * @return can be rendered */ EFUSION_API std::map & getFeedbackBuffers(); /** * Calculate the above for the current frame (only done on the first frame normally) */ EFUSION_API void computeFeedbackBuffers(); /** * Saves out a .ply mesh file of the current model */ EFUSION_API void savePly(); /** * Renders a normalised view of the input raw depth for displaying as an OpenGL texture * (this is stored under textures[GPUTexture::DEPTH_NORM] * @param minVal minimum depth value to render * @param maxVal maximum depth value to render */ EFUSION_API void normaliseDepth(const float & minVal, const float & maxVal); //Here be dragons //cuong std::string saveFilename; private: IndexMap indexMap; RGBDOdometry frameToModel; RGBDOdometry modelToModel; GlobalModel globalModel; FillIn fillIn; Ferns ferns; Deformation localDeformation; Deformation globalDeformation; std::map textures; std::map computePacks; std::map feedbackBuffers; void createTextures(); void createCompute(); void createFeedbackBuffers(); void filterDepth(); void metriciseDepth(); bool denseEnough(const Img> & img); void processFerns(); Eigen::Vector3f rodrigues2(const Eigen::Matrix3f& matrix); Eigen::Matrix4f currPose; int tick; const int timeDelta; const int icpCountThresh; const float icpErrThresh; const float covThresh; int deforms; int fernDeforms; const int consSample; Resize resize; std::vector poseMatches; std::vector relativeCons; std::vector > poseGraph; std::vector poseLogTimes; Img> imageBuff; Img consBuff; Img timesBuff; const bool closeLoops; const bool iclnuim; const bool reloc; bool lost; bool lastFrameRecovery; int trackingCount; const float maxDepthProcessed; bool rgbOnly; float icpWeight; bool pyramid; bool fastOdom; float confidenceThreshold; float fernThresh; bool so3; bool frameToFrameRGB; float depthCutoff; }; #endif /* ELASTICFUSION_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Ferns.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "Ferns.h" Ferns::Ferns(int n, int maxDepth, const float photoThresh) : num(n), factor(8), width(Resolution::getInstance().width() / factor), height(Resolution::getInstance().height() / factor), maxDepth(maxDepth), photoThresh(photoThresh), widthDist(0, width - 1), heightDist(0, height - 1), rgbDist(0, 255), dDist(400, maxDepth), lastClosest(-1), badCode(255), rgbd(Resolution::getInstance().width() / factor, Resolution::getInstance().height() / factor, Intrinsics::getInstance().cx() / factor, Intrinsics::getInstance().cy() / factor, Intrinsics::getInstance().fx() / factor, Intrinsics::getInstance().fy() / factor), vertFern(width, height, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), vertCurrent(width, height, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), normFern(width, height, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), normCurrent(width, height, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), colorFern(width, height, GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), colorCurrent(width, height, GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), resize(Resolution::getInstance().width(), Resolution::getInstance().height(), width, height), imageBuff(width, height), vertBuff(width, height), normBuff(width, height) { random.seed(time(0)); generateFerns(); } Ferns::~Ferns() { for(size_t i = 0; i < frames.size(); i++) { delete frames.at(i); } } void Ferns::generateFerns() { for(int i = 0; i < num; i++) { Fern f; f.pos(0) = widthDist(random); f.pos(1) = heightDist(random); f.rgbd(0) = rgbDist(random); f.rgbd(1) = rgbDist(random); f.rgbd(2) = rgbDist(random); f.rgbd(3) = dDist(random); conservatory.push_back(f); } } bool Ferns::addFrame(GPUTexture * imageTexture, GPUTexture * vertexTexture, GPUTexture * normalTexture, const Eigen::Matrix4f & pose, int srcTime, const float threshold) { Img> img(height, width); Img verts(height, width); Img norms(height, width); resize.image(imageTexture, img); resize.vertex(vertexTexture, verts); resize.vertex(normalTexture, norms); Frame * frame = new Frame(num, frames.size(), pose, srcTime, width * height, (unsigned char *)img.data, (Eigen::Vector4f *)verts.data, (Eigen::Vector4f *)norms.data); int * coOccurrences = new int[frames.size()]; memset(coOccurrences, 0, sizeof(int) * frames.size()); for(int i = 0; i < num; i++) { unsigned char code = badCode; if(verts.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) > 0) { const Eigen::Matrix & pix = img.at>(conservatory.at(i).pos(1), conservatory.at(i).pos(0)); code = (pix(0) > conservatory.at(i).rgbd(0)) << 3 | (pix(1) > conservatory.at(i).rgbd(1)) << 2 | (pix(2) > conservatory.at(i).rgbd(2)) << 1 | (int(verts.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) * 1000.0f) > conservatory.at(i).rgbd(3)); frame->goodCodes++; for(size_t j = 0; j < conservatory.at(i).ids[code].size(); j++) { coOccurrences[conservatory.at(i).ids[code].at(j)]++; } } frame->codes[i] = code; } float minimum = std::numeric_limits::max(); if(frame->goodCodes > 0) { for(size_t i = 0; i < frames.size(); i++) { float maxCo = std::min(frame->goodCodes, frames.at(i)->goodCodes); float dissim = (float)(maxCo - coOccurrences[i]) / (float)maxCo; if(dissim < minimum) { minimum = dissim; } } } delete [] coOccurrences; if((minimum > threshold || frames.size() == 0) && frame->goodCodes > 0) { for(int i = 0; i < num; i++) { if(frame->codes[i] != badCode) { conservatory.at(i).ids[frame->codes[i]].push_back(frame->id); } } frames.push_back(frame); return true; } else { delete frame; return false; } } Eigen::Matrix4f Ferns::findFrame(std::vector & constraints, const Eigen::Matrix4f & currPose, GPUTexture * vertexTexture, GPUTexture * normalTexture, GPUTexture * imageTexture, const int time, const bool lost) { lastClosest = -1; Img> imgSmall(height, width); Img vertSmall(height, width); Img normSmall(height, width); resize.image(imageTexture, imgSmall); resize.vertex(vertexTexture, vertSmall); resize.vertex(normalTexture, normSmall); Frame * frame = new Frame(num, 0, Eigen::Matrix4f::Identity(), 0, width * height); int * coOccurrences = new int[frames.size()]; memset(coOccurrences, 0, sizeof(int) * frames.size()); for(int i = 0; i < num; i++) { unsigned char code = badCode; if(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) > 0) { const Eigen::Matrix & pix = imgSmall.at>(conservatory.at(i).pos(1), conservatory.at(i).pos(0)); code = (pix(0) > conservatory.at(i).rgbd(0)) << 3 | (pix(1) > conservatory.at(i).rgbd(1)) << 2 | (pix(2) > conservatory.at(i).rgbd(2)) << 1 | (int(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) * 1000.0f) > conservatory.at(i).rgbd(3)); frame->goodCodes++; for(size_t j = 0; j < conservatory.at(i).ids[code].size(); j++) { coOccurrences[conservatory.at(i).ids[code].at(j)]++; } } frame->codes[i] = code; } float minimum = std::numeric_limits::max(); int minId = -1; for(size_t i = 0; i < frames.size(); i++) { float maxCo = std::min(frame->goodCodes, frames.at(i)->goodCodes); float dissim = (float)(maxCo - coOccurrences[i]) / (float)maxCo; if(dissim < minimum && time - frames.at(i)->srcTime > 300) { minimum = dissim; minId = i; } } delete [] coOccurrences; Eigen::Matrix4f estPose = Eigen::Matrix4f::Identity(); if(minId != -1 && blockHDAware(frame, frames.at(minId)) > 0.3) { Eigen::Matrix4f fernPose = frames.at(minId)->pose; vertFern.texture->Upload(frames.at(minId)->initVerts, GL_RGBA, GL_FLOAT); vertCurrent.texture->Upload(vertSmall.data, GL_RGBA, GL_FLOAT); normFern.texture->Upload(frames.at(minId)->initNorms, GL_RGBA, GL_FLOAT); normCurrent.texture->Upload(normSmall.data, GL_RGBA, GL_FLOAT); // colorFern.texture->Upload(frames.at(minId)->initRgb, GL_RGB, GL_UNSIGNED_BYTE); // colorCurrent.texture->Upload(imgSmall.data, GL_RGB, GL_UNSIGNED_BYTE); //WARNING initICP* must be called before initRGB* rgbd.initICPModel(&vertFern, &normFern, (float)maxDepth / 1000.0f, fernPose); // rgbd.initRGBModel(&colorFern); rgbd.initICP(&vertCurrent, &normCurrent, (float)maxDepth / 1000.0f); // rgbd.initRGB(&colorCurrent); Eigen::Vector3f trans = fernPose.topRightCorner(3, 1); Eigen::Matrix rot = fernPose.topLeftCorner(3, 3); TICK("fernOdom"); rgbd.getIncrementalTransformation(trans, rot, false, 100, false, false, false); TOCK("fernOdom"); estPose.topRightCorner(3, 1) = trans; estPose.topLeftCorner(3, 3) = rot; float photoError = photometricCheck(vertSmall, imgSmall, estPose, fernPose, frames.at(minId)->initRgb); int icpCountThresh = lost ? 1400 : 2400; // std::cout << rgbd.lastICPError << ", " << rgbd.lastICPCount << ", " << photoError << std::endl; if(rgbd.lastICPError < 0.0003 && rgbd.lastICPCount > icpCountThresh && photoError < photoThresh) { lastClosest = minId; for(int i = 0; i < num; i += num / 50) { if(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) > 0 && int(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) * 1000.0f) < maxDepth) { Eigen::Vector4f worldRawPoint = currPose * Eigen::Vector4f(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(0), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(1), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2), 1.0f); Eigen::Vector4f worldModelPoint = estPose * Eigen::Vector4f(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(0), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(1), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2), 1.0f); constraints.push_back(SurfaceConstraint(worldRawPoint, worldModelPoint)); } } } } delete frame; return estPose; } float Ferns::photometricCheck(const Img & vertSmall, const Img> & imgSmall, const Eigen::Matrix4f & estPose, const Eigen::Matrix4f & fernPose, const unsigned char * fernRgb) { float cx = Intrinsics::getInstance().cx() / factor; float cy = Intrinsics::getInstance().cy() / factor; float invfx = 1.0f / float(Intrinsics::getInstance().fx() / factor); float invfy = 1.0f / float(Intrinsics::getInstance().fy() / factor); Img> imgFern(height, width, (Eigen::Matrix *)fernRgb); float photoSum = 0; int photoCount = 0; for(int i = 0; i < num; i++) { if(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) > 0 && int(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2) * 1000.0f) < maxDepth) { Eigen::Vector4f vertPoint = Eigen::Vector4f(vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(0), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(1), vertSmall.at(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2), 1.0f); Eigen::Matrix4f diff = fernPose.inverse() * estPose; Eigen::Vector4f worldCorrPoint = diff * vertPoint; Eigen::Vector2i correspondence((worldCorrPoint(0) * (1/invfx) / worldCorrPoint(2) + cx), (worldCorrPoint(1) * (1/invfy) / worldCorrPoint(2) + cy)); if(correspondence(0) >= 0 && correspondence(1) >= 0 && correspondence(0) < width && correspondence(1) < height && (imgFern.at>(correspondence(1), correspondence(0))(0) > 0 || imgFern.at>(correspondence(1), correspondence(0))(1) > 0 || imgFern.at>(correspondence(1), correspondence(0))(2) > 0)) { photoSum += abs((int)imgFern.at>(correspondence(1), correspondence(0))(0) - (int)imgSmall.at>(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(0)); photoSum += abs((int)imgFern.at>(correspondence(1), correspondence(0))(1) - (int)imgSmall.at>(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(1)); photoSum += abs((int)imgFern.at>(correspondence(1), correspondence(0))(2) - (int)imgSmall.at>(conservatory.at(i).pos(1), conservatory.at(i).pos(0))(2)); photoCount++; } } } return photoSum / float(photoCount); } float Ferns::blockHD(const Frame * f1, const Frame * f2) { float sum = 0.0f; for(int i = 0; i < num; i++) { sum += f1->codes[i] == f2->codes[i]; } sum /= (float)num; return sum; } float Ferns::blockHDAware(const Frame * f1, const Frame * f2) { int count = 0; float val = 0; for(int i = 0; i < num; i++) { if(f1->codes[i] != badCode && f2->codes[i] != badCode) { count++; if(f1->codes[i] == f2->codes[i]) { val += 1.0f; } } } return val / (float)count; } ================================================ FILE: obj_pose_est/mapping/Core/src/Ferns.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef FERNS_H_ #define FERNS_H_ #include #include #include #include #include #include "Utils/Resolution.h" #include "Utils/Intrinsics.h" #include "Utils/RGBDOdometry.h" #include "Shaders/Resize.h" class Ferns { public: Ferns(int n, int maxDepth, const float photoThresh); virtual ~Ferns(); bool addFrame(GPUTexture * imageTexture, GPUTexture * vertexTexture, GPUTexture * normalTexture, const Eigen::Matrix4f & pose, int srcTime, const float threshold); class SurfaceConstraint { public: SurfaceConstraint(const Eigen::Vector4f & sourcePoint, const Eigen::Vector4f & targetPoint) : sourcePoint(sourcePoint), targetPoint(targetPoint) {} Eigen::Vector4f sourcePoint; Eigen::Vector4f targetPoint; }; Eigen::Matrix4f findFrame(std::vector & constraints, const Eigen::Matrix4f & currPose, GPUTexture * vertexTexture, GPUTexture * normalTexture, GPUTexture * imageTexture, const int time, const bool lost); class Fern { public: Fern() {} Eigen::Vector2i pos; Eigen::Vector4i rgbd; std::vector ids[16]; }; std::vector conservatory; class Frame { public: Frame(int n, int id, const Eigen::Matrix4f & pose, const int srcTime, const int numPixels, unsigned char * rgb = 0, Eigen::Vector4f * verts = 0, Eigen::Vector4f * norms = 0) : goodCodes(0), id(id), pose(pose), srcTime(srcTime), initRgb(rgb), initVerts(verts), initNorms(norms) { codes = new unsigned char[n]; if(rgb) { this->initRgb = new unsigned char[numPixels * 3]; memcpy(this->initRgb, rgb, numPixels * 3); } if(verts) { this->initVerts = new Eigen::Vector4f[numPixels]; memcpy(this->initVerts, verts, numPixels * sizeof(Eigen::Vector4f)); } if(norms) { this->initNorms = new Eigen::Vector4f[numPixels]; memcpy(this->initNorms, norms, numPixels * sizeof(Eigen::Vector4f)); } } virtual ~Frame() { delete [] codes; if(initRgb) delete [] initRgb; if(initVerts) delete [] initVerts; if(initNorms) delete [] initNorms; } unsigned char * codes; int goodCodes; const int id; Eigen::Matrix4f pose; const int srcTime; unsigned char * initRgb; Eigen::Vector4f * initVerts; Eigen::Vector4f * initNorms; }; std::vector frames; const int num; std::mt19937 random; const int factor; const int width; const int height; const int maxDepth; const float photoThresh; std::uniform_int_distribution widthDist; std::uniform_int_distribution heightDist; std::uniform_int_distribution rgbDist; std::uniform_int_distribution dDist; int lastClosest; const unsigned char badCode; RGBDOdometry rgbd; private: void generateFerns(); float blockHD(const Frame * f1, const Frame * f2); float blockHDAware(const Frame * f1, const Frame * f2); float photometricCheck(const Img & vertSmall, const Img> & imgSmall, const Eigen::Matrix4f & estPose, const Eigen::Matrix4f & fernPose, const unsigned char * fernRgb); GPUTexture vertFern; GPUTexture vertCurrent; GPUTexture normFern; GPUTexture normCurrent; GPUTexture colorFern; GPUTexture colorCurrent; Resize resize; Img> imageBuff; Img vertBuff; Img normBuff; }; #endif /* FERNS_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/FindSuiteSparse.cmake ================================================ # - Try to find SUITESPARSE # Once done this will define # # SUITESPARSE_FOUND - system has SUITESPARSE # SUITESPARSE_INCLUDE_DIRS - the SUITESPARSE include directory # SUITESPARSE_LIBRARIES - Link these to use SUITESPARSE # SUITESPARSE_SPQR_LIBRARY - name of spqr library (necessary due to error in debian package) # SUITESPARSE_SPQR_LIBRARY_DIR - name of spqr library (necessary due to error in debian package) # SUITESPARSE_LIBRARY_DIR - Library main directory containing suitesparse libs # SUITESPARSE_LIBRARY_DIRS - all Library directories containing suitesparse libs # SUITESPARSE_SPQR_VALID - automatic identification whether or not spqr package is installed correctly IF (SUITESPARSE_INCLUDE_DIRS) # Already in cache, be silent SET(SUITESPARSE_FIND_QUIETLY TRUE) ENDIF (SUITESPARSE_INCLUDE_DIRS) if (WIN32) # the libraries may have lib prefix set(ORIGINAL_CMAKE_FIND_LIBRARY_PREFIXES "${CMAKE_FIND_LIBRARY_PREFIXES}") set(CMAKE_FIND_LIBRARY_PREFIXES "lib" "" "${CMAKE_FIND_LIBRARY_PREFIXES}") endif () FIND_PATH( SUITESPARSE_INCLUDE_DIR cholmod.h PATHS /usr/local/include /usr/include /usr/include/suitesparse/ ${CMAKE_SOURCE_DIR}/MacOS/Libs/cholmod PATH_SUFFIXES cholmod/ CHOLMOD/ ) FIND_PATH( SUITESPARSE_LIBRARY_DIR NAMES libcholmod.so libcholmod.a PATHS /usr/lib /usr/lib64 /usr/lib/x86_64-linux-gnu /usr/lib/i386-linux-gnu /usr/local/lib ) # Add cholmod include directory to collection include directories IF ( SUITESPARSE_INCLUDE_DIR ) list ( APPEND SUITESPARSE_INCLUDE_DIRS ${SUITESPARSE_INCLUDE_DIR} ) ENDIF( SUITESPARSE_INCLUDE_DIR ) # if we found the library, add it to the defined libraries IF ( SUITESPARSE_LIBRARY_DIR ) FIND_LIBRARY( SUITESPARSE_AMD_LIBRARY NAMES amd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CAMD_LIBRARY NAMES camd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CCOLAMD_LIBRARY NAMES ccolamd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CHOLMOD_LIBRARY NAMES cholmod PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_COLAMD_LIBRARY NAMES colamd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CXSPARSE_LIBRARY NAMES cxsparse PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF ( WIN32 ) FIND_LIBRARY( SUITESPARSE_SUITESPARSECONFIG_LIBRARY NAMES suitesparseconfig PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_BLAS_LIBRARY NAMES blas PATHS ${SUITESPARSE_LIBRARY_DIR}/lapack_blas_windows ) FIND_LIBRARY( SUITESPARSE_LAPACK_LIBRARY NAMES lapack PATHS ${SUITESPARSE_LIBRARY_DIR}/lapack_blas_windows ) ENDIF () list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_AMD_LIBRARY} ${SUITESPARSE_CAMD_LIBRARY} ${SUITESPARSE_CCOLAMD_LIBRARY} ${SUITESPARSE_CHOLMOD_LIBRARY} ${SUITESPARSE_COLAMD_LIBRARY} ${SUITESPARSE_CXSPARSE_LIBRARY} ${SUITESPARSE_SUITESPARSECONFIG_LIBRARY} ${SUITESPARSE_BLAS_LIBRARY} ${SUITESPARSE_LAPACK_LIBRARY}) # Metis and spqr are optional FIND_LIBRARY( SUITESPARSE_METIS_LIBRARY NAMES metis PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF (SUITESPARSE_METIS_LIBRARY) list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_METIS_LIBRARY}) ENDIF(SUITESPARSE_METIS_LIBRARY) if(EXISTS "${SUITESPARSE_INCLUDE_DIR}/SuiteSparseQR.hpp") SET(SUITESPARSE_SPQR_VALID TRUE CACHE BOOL "SuiteSparseSPQR valid") else() SET(SUITESPARSE_SPQR_VALID false CACHE BOOL "SuiteSparseSPQR valid") endif() if(SUITESPARSE_SPQR_VALID) FIND_LIBRARY( SUITESPARSE_SPQR_LIBRARY NAMES spqr PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF (SUITESPARSE_SPQR_LIBRARY) list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_SPQR_LIBRARY}) ENDIF (SUITESPARSE_SPQR_LIBRARY) endif() ENDIF( SUITESPARSE_LIBRARY_DIR ) IF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) SET(SUITESPARSE_FOUND TRUE) MESSAGE(STATUS "Found SuiteSparse") ELSE (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) SET( SUITESPARSE_FOUND FALSE ) MESSAGE(FATAL_ERROR "Unable to find SuiteSparse") ENDIF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) if (WIN32) set(CMAKE_FIND_LIBRARY_PREFIXES "${ORIGINAL_CMAKE_FIND_LIBRARY_PREFIXES}") endif () ================================================ FILE: obj_pose_est/mapping/Core/src/GPUTexture.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "GPUTexture.h" const std::string GPUTexture::RGB = "RGB"; const std::string GPUTexture::DEPTH_RAW = "DEPTH"; const std::string GPUTexture::DEPTH_FILTERED = "DEPTH_FILTERED"; const std::string GPUTexture::DEPTH_METRIC = "DEPTH_METRIC"; const std::string GPUTexture::DEPTH_METRIC_FILTERED = "DEPTH_METRIC_FILTERED"; const std::string GPUTexture::DEPTH_NORM = "DEPTH_NORM"; GPUTexture::GPUTexture(const int width, const int height, const GLenum internalFormat, const GLenum format, const GLenum dataType, const bool draw, const bool cuda) : texture(new pangolin::GlTexture(width, height, internalFormat, draw, 0, format, dataType)), draw(draw), width(width), height(height), internalFormat(internalFormat), format(format), dataType(dataType) { if(cuda) { cudaGraphicsGLRegisterImage(&cudaRes, texture->tid, GL_TEXTURE_2D, cudaGraphicsRegisterFlagsReadOnly); } else { cudaRes = 0; } } GPUTexture::~GPUTexture() { if(texture) { delete texture; } if(cudaRes) { cudaGraphicsUnregisterResource(cudaRes); } } void GPUTexture::save(const std::string& file) { // cudaDeviceSynchronize(); if (cudaRes) cudaSafeCall(cudaGraphicsUnmapResources(1, &cudaRes)); texture->Save(file); if (cudaRes) cudaSafeCall(cudaGraphicsMapResources(1, &cudaRes)); } ================================================ FILE: obj_pose_est/mapping/Core/src/GPUTexture.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef GPUTEXTURE_H_ #define GPUTEXTURE_H_ #include #include #include #include #include "Cuda/convenience.cuh" #include #include #include "Defines.h" class GPUTexture { public: EFUSION_API GPUTexture(const int width, const int height, const GLenum internalFormat, const GLenum format, const GLenum dataType, const bool draw = false, const bool cuda = false); virtual ~GPUTexture(); void save(const std::string& file); EFUSION_API static const std::string RGB, DEPTH_RAW, DEPTH_FILTERED, DEPTH_METRIC, DEPTH_METRIC_FILTERED, DEPTH_NORM; pangolin::GlTexture * texture; cudaGraphicsResource * cudaRes; const bool draw; private: GPUTexture() : texture(0), cudaRes(0), draw(false), width(0), height(0), internalFormat(0), format(0), dataType(0) {} const int width; const int height; const GLenum internalFormat; const GLenum format; const GLenum dataType; }; #endif /* GPUTEXTURE_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/GlobalModel.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "GlobalModel.h" const int GlobalModel::TEXTURE_DIMENSION = 3072; const int GlobalModel::MAX_VERTICES = GlobalModel::TEXTURE_DIMENSION * GlobalModel::TEXTURE_DIMENSION; const int GlobalModel::NODE_TEXTURE_DIMENSION = 16384; const int GlobalModel::MAX_NODES = GlobalModel::NODE_TEXTURE_DIMENSION / 16; //16 floats per node GlobalModel::GlobalModel() : target(0), renderSource(1), bufferSize(MAX_VERTICES * Vertex::SIZE), count(0), initProgram(loadProgramFromFile("init_unstable.vert")), drawProgram(loadProgramFromFile("draw_feedback.vert", "draw_feedback.frag")), drawSurfelProgram(loadProgramFromFile("draw_global_surface.vert", "draw_global_surface.frag", "draw_global_surface.geom")), dataProgram(loadProgramFromFile("data.vert", "data.frag", "data.geom")), updateProgram(loadProgramFromFile("update.vert")), unstableProgram(loadProgramGeomFromFile("copy_unstable.vert", "copy_unstable.geom")), renderBuffer(TEXTURE_DIMENSION, TEXTURE_DIMENSION), updateMapVertsConfs(TEXTURE_DIMENSION, TEXTURE_DIMENSION, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), updateMapColorsTime(TEXTURE_DIMENSION, TEXTURE_DIMENSION, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), updateMapNormsRadii(TEXTURE_DIMENSION, TEXTURE_DIMENSION, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), deformationNodes(NODE_TEXTURE_DIMENSION, 1, GL_LUMINANCE32F_ARB, GL_LUMINANCE, GL_FLOAT) { vbos = new std::pair[2]; float * vertices = new float[bufferSize]; memset(&vertices[0], 0, bufferSize); glGenTransformFeedbacks(1, &vbos[0].second); glGenBuffers(1, &vbos[0].first); glBindBuffer(GL_ARRAY_BUFFER, vbos[0].first); glBufferData(GL_ARRAY_BUFFER, bufferSize, &vertices[0], GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); glGenTransformFeedbacks(1, &vbos[1].second); glGenBuffers(1, &vbos[1].first); glBindBuffer(GL_ARRAY_BUFFER, vbos[1].first); glBufferData(GL_ARRAY_BUFFER, bufferSize, &vertices[0], GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); delete [] vertices; vertices = new float[Resolution::getInstance().numPixels() * Vertex::SIZE]; memset(&vertices[0], 0, Resolution::getInstance().numPixels() * Vertex::SIZE); glGenTransformFeedbacks(1, &newUnstableFid); glGenBuffers(1, &newUnstableVbo); glBindBuffer(GL_ARRAY_BUFFER, newUnstableVbo); glBufferData(GL_ARRAY_BUFFER, Resolution::getInstance().numPixels() * Vertex::SIZE, &vertices[0], GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); delete [] vertices; std::vector uv; for(int i = 0; i < Resolution::getInstance().width(); i++) { for(int j = 0; j < Resolution::getInstance().height(); j++) { uv.push_back(Eigen::Vector2f(((float)i / (float)Resolution::getInstance().width()) + 1.0 / (2 * (float)Resolution::getInstance().width()), ((float)j / (float)Resolution::getInstance().height()) + 1.0 / (2 * (float)Resolution::getInstance().height()))); } } uvSize = uv.size(); glGenBuffers(1, &uvo); glBindBuffer(GL_ARRAY_BUFFER, uvo); glBufferData(GL_ARRAY_BUFFER, uvSize * sizeof(Eigen::Vector2f), &uv[0], GL_STATIC_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); frameBuffer.AttachColour(*updateMapVertsConfs.texture); frameBuffer.AttachColour(*updateMapColorsTime.texture); frameBuffer.AttachColour(*updateMapNormsRadii.texture); frameBuffer.AttachDepth(renderBuffer); updateProgram->Bind(); int locUpdate[3] = { glGetVaryingLocationNV(updateProgram->programId(), "vPosition0"), glGetVaryingLocationNV(updateProgram->programId(), "vColor0"), glGetVaryingLocationNV(updateProgram->programId(), "vNormRad0"), }; glTransformFeedbackVaryingsNV(updateProgram->programId(), 3, locUpdate, GL_INTERLEAVED_ATTRIBS); updateProgram->Unbind(); dataProgram->Bind(); int dataUpdate[3] = { glGetVaryingLocationNV(dataProgram->programId(), "vPosition0"), glGetVaryingLocationNV(dataProgram->programId(), "vColor0"), glGetVaryingLocationNV(dataProgram->programId(), "vNormRad0"), }; glTransformFeedbackVaryingsNV(dataProgram->programId(), 3, dataUpdate, GL_INTERLEAVED_ATTRIBS); dataProgram->Unbind(); unstableProgram->Bind(); int unstableUpdate[3] = { glGetVaryingLocationNV(unstableProgram->programId(), "vPosition0"), glGetVaryingLocationNV(unstableProgram->programId(), "vColor0"), glGetVaryingLocationNV(unstableProgram->programId(), "vNormRad0"), }; glTransformFeedbackVaryingsNV(unstableProgram->programId(), 3, unstableUpdate, GL_INTERLEAVED_ATTRIBS); unstableProgram->Unbind(); initProgram->Bind(); int locInit[3] = { glGetVaryingLocationNV(initProgram->programId(), "vPosition0"), glGetVaryingLocationNV(initProgram->programId(), "vColor0"), glGetVaryingLocationNV(initProgram->programId(), "vNormRad0"), }; glTransformFeedbackVaryingsNV(initProgram->programId(), 3, locInit, GL_INTERLEAVED_ATTRIBS); glGenQueries(1, &countQuery); //Empty both transform feedbacks glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, vbos[0].second); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbos[0].first); glBeginTransformFeedback(GL_POINTS); glDrawArrays(GL_POINTS, 0, 0); glEndTransformFeedback(); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, vbos[1].second); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbos[1].first); glBeginTransformFeedback(GL_POINTS); glDrawArrays(GL_POINTS, 0, 0); glEndTransformFeedback(); glDisable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); initProgram->Unbind(); } GlobalModel::~GlobalModel() { glDeleteBuffers(1, &vbos[0].first); glDeleteTransformFeedbacks(1, &vbos[0].second); glDeleteBuffers(1, &vbos[1].first); glDeleteTransformFeedbacks(1, &vbos[1].second); glDeleteQueries(1, &countQuery); glDeleteBuffers(1, &uvo); glDeleteTransformFeedbacks(1, &newUnstableFid); glDeleteBuffers(1, &newUnstableVbo); delete [] vbos; } void GlobalModel::initialise(const FeedbackBuffer & rawFeedback, const FeedbackBuffer & filteredFeedback) { initProgram->Bind(); glBindBuffer(GL_ARRAY_BUFFER, rawFeedback.vbo); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glBindBuffer(GL_ARRAY_BUFFER, filteredFeedback.vbo); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, vbos[target].second); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbos[target].first); glBeginTransformFeedback(GL_POINTS); glBeginQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN, countQuery); //It's ok to use either fid because both raw and filtered have the same amount of vertices glDrawTransformFeedback(GL_POINTS, rawFeedback.fid); glEndTransformFeedback(); glEndQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN); glGetQueryObjectuiv(countQuery, GL_QUERY_RESULT, &count); glDisable(GL_RASTERIZER_DISCARD); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); initProgram->Unbind(); glFinish(); } void GlobalModel::renderPointCloud(pangolin::OpenGlMatrix mvp, const float threshold, const bool drawUnstable, const bool drawNormals, const bool drawColors, const bool drawPoints, const bool drawWindow, const bool drawTimes, const int time, const int timeDelta) { std::shared_ptr program = drawPoints ? drawProgram : drawSurfelProgram; program->Bind(); program->setUniform(Uniform("MVP", mvp)); program->setUniform(Uniform("threshold", threshold)); program->setUniform(Uniform("colorType", (drawNormals ? 1 : drawColors ? 2 : drawTimes ? 3 : 0))); program->setUniform(Uniform("unstable", drawUnstable)); program->setUniform(Uniform("drawWindow", drawWindow)); program->setUniform(Uniform("time", time)); program->setUniform(Uniform("timeDelta", timeDelta)); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); //This is for the point shader program->setUniform(Uniform("pose", pose)); glBindBuffer(GL_ARRAY_BUFFER, vbos[target].first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, vbos[target].second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); program->Unbind(); } const std::pair & GlobalModel::model() { return vbos[target]; } void GlobalModel::fuse(const Eigen::Matrix4f & pose, const int & time, GPUTexture * rgb, GPUTexture * depthRaw, GPUTexture * depthFiltered, GPUTexture * indexMap, GPUTexture * vertConfMap, GPUTexture * colorTimeMap, GPUTexture * normRadMap, const float depthCutoff, const float confThreshold, const float weighting) { TICK("Fuse::Data"); //This first part does data association and computes the vertex to merge with, storing //in an array that sets which vertices to update by index frameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, renderBuffer.width, renderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); dataProgram->Bind(); dataProgram->setUniform(Uniform("cSampler", 0)); dataProgram->setUniform(Uniform("drSampler", 1)); dataProgram->setUniform(Uniform("drfSampler", 2)); dataProgram->setUniform(Uniform("indexSampler", 3)); dataProgram->setUniform(Uniform("vertConfSampler", 4)); dataProgram->setUniform(Uniform("colorTimeSampler", 5)); dataProgram->setUniform(Uniform("normRadSampler", 6)); dataProgram->setUniform(Uniform("time", (float)time)); dataProgram->setUniform(Uniform("weighting", weighting)); dataProgram->setUniform(Uniform("cam", Eigen::Vector4f(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), 1.0 / Intrinsics::getInstance().fx(), 1.0 / Intrinsics::getInstance().fy()))); dataProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); dataProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); dataProgram->setUniform(Uniform("scale", (float)IndexMap::FACTOR)); dataProgram->setUniform(Uniform("texDim", (float)TEXTURE_DIMENSION)); dataProgram->setUniform(Uniform("pose", pose)); dataProgram->setUniform(Uniform("maxDepth", depthCutoff)); glEnableVertexAttribArray(0); glBindBuffer(GL_ARRAY_BUFFER, uvo); glVertexAttribPointer(0, 2, GL_FLOAT, GL_FALSE, 0, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, newUnstableFid); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, newUnstableVbo); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, rgb->texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, depthRaw->texture->tid); glActiveTexture(GL_TEXTURE2); glBindTexture(GL_TEXTURE_2D, depthFiltered->texture->tid); glActiveTexture(GL_TEXTURE3); glBindTexture(GL_TEXTURE_2D, indexMap->texture->tid); glActiveTexture(GL_TEXTURE4); glBindTexture(GL_TEXTURE_2D, vertConfMap->texture->tid); glActiveTexture(GL_TEXTURE5); glBindTexture(GL_TEXTURE_2D, colorTimeMap->texture->tid); glActiveTexture(GL_TEXTURE6); glBindTexture(GL_TEXTURE_2D, normRadMap->texture->tid); glBeginTransformFeedback(GL_POINTS); glDrawArrays(GL_POINTS, 0, uvSize); glEndTransformFeedback(); frameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); glDisableVertexAttribArray(0); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); dataProgram->Unbind(); glPopAttrib(); glFinish(); TOCK("Fuse::Data"); TICK("Fuse::Update"); //Next we update the vertices at the indexes stored in the update textures //Using a transform feedback conditional on a texture sample updateProgram->Bind(); updateProgram->setUniform(Uniform("vertSamp", 0)); updateProgram->setUniform(Uniform("colorSamp", 1)); updateProgram->setUniform(Uniform("normSamp", 2)); updateProgram->setUniform(Uniform("texDim", (float)TEXTURE_DIMENSION)); updateProgram->setUniform(Uniform("time", time)); glBindBuffer(GL_ARRAY_BUFFER, vbos[target].first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, vbos[renderSource].second); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbos[renderSource].first); glBeginTransformFeedback(GL_POINTS); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, updateMapVertsConfs.texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, updateMapColorsTime.texture->tid); glActiveTexture(GL_TEXTURE2); glBindTexture(GL_TEXTURE_2D, updateMapNormsRadii.texture->tid); glDrawTransformFeedback(GL_POINTS, vbos[target].second); glEndTransformFeedback(); glDisable(GL_RASTERIZER_DISCARD); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); updateProgram->Unbind(); std::swap(target, renderSource); glFinish(); TOCK("Fuse::Update"); } void GlobalModel::clean(const Eigen::Matrix4f & pose, const int & time, GPUTexture * indexMap, GPUTexture * vertConfMap, GPUTexture * colorTimeMap, GPUTexture * normRadMap, GPUTexture * depthMap, const float confThreshold, std::vector & graph, const int timeDelta, const float maxDepth, const bool isFern) { assert(graph.size() / 16 < MAX_NODES); if(graph.size() > 0) { //Can be optimised by only uploading new nodes with offset glBindTexture(GL_TEXTURE_2D, deformationNodes.texture->tid); glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, graph.size(), 1, GL_LUMINANCE, GL_FLOAT, graph.data()); } TICK("Fuse::Copy"); //Next we copy the new unstable vertices from the newUnstableFid transform feedback into the global map unstableProgram->Bind(); unstableProgram->setUniform(Uniform("time", time)); unstableProgram->setUniform(Uniform("confThreshold", confThreshold)); unstableProgram->setUniform(Uniform("scale", (float)IndexMap::FACTOR)); unstableProgram->setUniform(Uniform("indexSampler", 0)); unstableProgram->setUniform(Uniform("vertConfSampler", 1)); unstableProgram->setUniform(Uniform("colorTimeSampler", 2)); unstableProgram->setUniform(Uniform("normRadSampler", 3)); unstableProgram->setUniform(Uniform("nodeSampler", 4)); unstableProgram->setUniform(Uniform("depthSampler", 5)); unstableProgram->setUniform(Uniform("nodes", (float)(graph.size() / 16))); unstableProgram->setUniform(Uniform("nodeCols", (float)NODE_TEXTURE_DIMENSION)); unstableProgram->setUniform(Uniform("timeDelta", timeDelta)); unstableProgram->setUniform(Uniform("maxDepth", maxDepth)); unstableProgram->setUniform(Uniform("isFern", (int)isFern)); Eigen::Matrix4f t_inv = pose.inverse(); unstableProgram->setUniform(Uniform("t_inv", t_inv)); unstableProgram->setUniform(Uniform("cam", Eigen::Vector4f(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()))); unstableProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); unstableProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); glBindBuffer(GL_ARRAY_BUFFER, vbos[target].first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, vbos[renderSource].second); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbos[renderSource].first); glBeginTransformFeedback(GL_POINTS); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, indexMap->texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, vertConfMap->texture->tid); glActiveTexture(GL_TEXTURE2); glBindTexture(GL_TEXTURE_2D, colorTimeMap->texture->tid); glActiveTexture(GL_TEXTURE3); glBindTexture(GL_TEXTURE_2D, normRadMap->texture->tid); glActiveTexture(GL_TEXTURE4); glBindTexture(GL_TEXTURE_2D, deformationNodes.texture->tid); glActiveTexture(GL_TEXTURE5); glBindTexture(GL_TEXTURE_2D, depthMap->texture->tid); glBeginQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN, countQuery); glDrawTransformFeedback(GL_POINTS, vbos[target].second); glBindBuffer(GL_ARRAY_BUFFER, newUnstableVbo); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, newUnstableFid); glEndQuery(GL_TRANSFORM_FEEDBACK_PRIMITIVES_WRITTEN); glGetQueryObjectuiv(countQuery, GL_QUERY_RESULT, &count); glEndTransformFeedback(); glDisable(GL_RASTERIZER_DISCARD); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); unstableProgram->Unbind(); std::swap(target, renderSource); glFinish(); TOCK("Fuse::Copy"); } unsigned int GlobalModel::lastCount() { return count; } Eigen::Vector4f * GlobalModel::downloadMap() { glFinish(); Eigen::Vector4f * vertices = new Eigen::Vector4f[count * 3]; memset(&vertices[0], 0, count * Vertex::SIZE); GLuint downloadVbo; glGenBuffers(1, &downloadVbo); glBindBuffer(GL_ARRAY_BUFFER, downloadVbo); glBufferData(GL_ARRAY_BUFFER, bufferSize, 0, GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindBuffer(GL_COPY_READ_BUFFER, vbos[renderSource].first); glBindBuffer(GL_COPY_WRITE_BUFFER, downloadVbo); glCopyBufferSubData(GL_COPY_READ_BUFFER, GL_COPY_WRITE_BUFFER, 0, 0, count * Vertex::SIZE); glGetBufferSubData(GL_COPY_WRITE_BUFFER, 0, count * Vertex::SIZE, vertices); glBindBuffer(GL_COPY_READ_BUFFER, 0); glBindBuffer(GL_COPY_WRITE_BUFFER, 0); glDeleteBuffers(1, &downloadVbo); glFinish(); return vertices; } ================================================ FILE: obj_pose_est/mapping/Core/src/GlobalModel.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef GLOBALMODEL_H_ #define GLOBALMODEL_H_ #include "Shaders/Shaders.h" #include "Shaders/Uniform.h" #include "Shaders/FeedbackBuffer.h" #include "GPUTexture.h" #include "Utils/Resolution.h" #include "IndexMap.h" #include "Utils/Stopwatch.h" #include "Utils/Intrinsics.h" #include #include #include "Defines.h" class GlobalModel { public: GlobalModel(); virtual ~GlobalModel(); void initialise(const FeedbackBuffer & rawFeedback, const FeedbackBuffer & filteredFeedback); static const int TEXTURE_DIMENSION; static const int MAX_VERTICES; static const int NODE_TEXTURE_DIMENSION; static const int MAX_NODES; EFUSION_API void renderPointCloud(pangolin::OpenGlMatrix mvp, const float threshold, const bool drawUnstable, const bool drawNormals, const bool drawColors, const bool drawPoints, const bool drawWindow, const bool drawTimes, const int time, const int timeDelta); EFUSION_API const std::pair & model(); void fuse(const Eigen::Matrix4f & pose, const int & time, GPUTexture * rgb, GPUTexture * depthRaw, GPUTexture * depthFiltered, GPUTexture * indexMap, GPUTexture * vertConfMap, GPUTexture * colorTimeMap, GPUTexture * normRadMap, const float depthCutoff, const float confThreshold, const float weighting); void clean(const Eigen::Matrix4f & pose, const int & time, GPUTexture * indexMap, GPUTexture * vertConfMap, GPUTexture * colorTimeMap, GPUTexture * normRadMap, GPUTexture * depthMap, const float confThreshold, std::vector & graph, const int timeDelta, const float maxDepth, const bool isFern); EFUSION_API unsigned int lastCount(); Eigen::Vector4f * downloadMap(); private: //First is the vbo, second is the fid std::pair * vbos; int target, renderSource; const int bufferSize; GLuint countQuery; unsigned int count; std::shared_ptr initProgram; std::shared_ptr drawProgram; std::shared_ptr drawSurfelProgram; //For supersample fusing std::shared_ptr dataProgram; std::shared_ptr updateProgram; std::shared_ptr unstableProgram; pangolin::GlRenderBuffer renderBuffer; //We render updated vertices vec3 + confidences to one texture GPUTexture updateMapVertsConfs; //We render updated colors vec3 + timestamps to another GPUTexture updateMapColorsTime; //We render updated normals vec3 + radii to another GPUTexture updateMapNormsRadii; //16 floats stored column-major yo' GPUTexture deformationNodes; GLuint newUnstableVbo, newUnstableFid; pangolin::GlFramebuffer frameBuffer; GLuint uvo; int uvSize; }; #endif /* GLOBALMODEL_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/IndexMap.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "IndexMap.h" const int IndexMap::FACTOR = 1; IndexMap::IndexMap() : indexProgram(loadProgramFromFile("index_map.vert", "index_map.frag")), indexRenderBuffer(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR), indexTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_LUMINANCE32UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_INT), vertConfTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), colorTimeTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), normalRadTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), drawDepthProgram(loadProgramFromFile("empty.vert", "visualise_textures.frag", "quad.geom")), drawRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), drawTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false), depthProgram(loadProgramFromFile("splat.vert", "depth_splat.frag")), depthRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), depthTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE32F_ARB, GL_LUMINANCE, GL_FLOAT, false, true), combinedProgram(loadProgramFromFile("splat.vert", "combo_splat.frag")), combinedRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), imageTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), vertexTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), normalTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), timeTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE16UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT, false, true), oldRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), oldImageTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), oldVertexTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), oldNormalTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), oldTimeTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_LUMINANCE16UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT, false, true), infoRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), colorInfoTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), vertexInfoTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT), normalInfoTexture(Resolution::getInstance().width() * IndexMap::FACTOR, Resolution::getInstance().height() * IndexMap::FACTOR, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT) { indexFrameBuffer.AttachColour(*indexTexture.texture); indexFrameBuffer.AttachColour(*vertConfTexture.texture); indexFrameBuffer.AttachColour(*colorTimeTexture.texture); indexFrameBuffer.AttachColour(*normalRadTexture.texture); indexFrameBuffer.AttachDepth(indexRenderBuffer); drawFrameBuffer.AttachColour(*drawTexture.texture); drawFrameBuffer.AttachDepth(drawRenderBuffer); depthFrameBuffer.AttachColour(*depthTexture.texture); depthFrameBuffer.AttachDepth(depthRenderBuffer); combinedFrameBuffer.AttachColour(*imageTexture.texture); combinedFrameBuffer.AttachColour(*vertexTexture.texture); combinedFrameBuffer.AttachColour(*normalTexture.texture); combinedFrameBuffer.AttachColour(*timeTexture.texture); combinedFrameBuffer.AttachDepth(combinedRenderBuffer); oldFrameBuffer.AttachDepth(oldRenderBuffer); oldFrameBuffer.AttachColour(*oldImageTexture.texture); oldFrameBuffer.AttachColour(*oldVertexTexture.texture); oldFrameBuffer.AttachColour(*oldNormalTexture.texture); oldFrameBuffer.AttachColour(*oldTimeTexture.texture); infoFrameBuffer.AttachColour(*colorInfoTexture.texture); infoFrameBuffer.AttachColour(*vertexInfoTexture.texture); infoFrameBuffer.AttachColour(*normalInfoTexture.texture); infoFrameBuffer.AttachDepth(infoRenderBuffer); } IndexMap::~IndexMap() { } void IndexMap::predictIndices(const Eigen::Matrix4f & pose, const int & time, const std::pair & model, const float depthCutoff, const int timeDelta) { indexFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, indexRenderBuffer.width, indexRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); indexProgram->Bind(); Eigen::Matrix4f t_inv = pose.inverse(); Eigen::Vector4f cam(Intrinsics::getInstance().cx() * IndexMap::FACTOR, Intrinsics::getInstance().cy() * IndexMap::FACTOR, Intrinsics::getInstance().fx() * IndexMap::FACTOR, Intrinsics::getInstance().fy() * IndexMap::FACTOR); indexProgram->setUniform(Uniform("t_inv", t_inv)); indexProgram->setUniform(Uniform("cam", cam)); indexProgram->setUniform(Uniform("maxDepth", depthCutoff)); indexProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols() * IndexMap::FACTOR)); indexProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows() * IndexMap::FACTOR)); indexProgram->setUniform(Uniform("time", time)); indexProgram->setUniform(Uniform("timeDelta", timeDelta)); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f))); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, model.second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); indexFrameBuffer.Unbind(); indexProgram->Unbind(); glPopAttrib(); glFinish(); } void IndexMap::renderDepth(const float depthCutoff) { drawFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, drawRenderBuffer.width, drawRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); drawDepthProgram->Bind(); drawDepthProgram->setUniform(Uniform("maxDepth", depthCutoff)); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, vertexTexture.texture->tid); drawDepthProgram->setUniform(Uniform("texVerts", 0)); glDrawArrays(GL_POINTS, 0, 1); drawFrameBuffer.Unbind(); drawDepthProgram->Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glPopAttrib(); glFinish(); } void IndexMap::combinedPredict(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold, const int time, const int maxTime, const int timeDelta, IndexMap::Prediction predictionType) { glEnable(GL_PROGRAM_POINT_SIZE); glEnable(GL_POINT_SPRITE); if(predictionType == IndexMap::ACTIVE) { combinedFrameBuffer.Bind(); } else if(predictionType == IndexMap::INACTIVE) { oldFrameBuffer.Bind(); } else { assert(false); } glPushAttrib(GL_VIEWPORT_BIT); if(predictionType == IndexMap::ACTIVE) { glViewport(0, 0, combinedRenderBuffer.width, combinedRenderBuffer.height); } else if(predictionType == IndexMap::INACTIVE) { glViewport(0, 0, oldRenderBuffer.width, oldRenderBuffer.height); } else { assert(false); } glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); combinedProgram->Bind(); Eigen::Matrix4f t_inv = pose.inverse(); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()); combinedProgram->setUniform(Uniform("t_inv", t_inv)); combinedProgram->setUniform(Uniform("cam", cam)); combinedProgram->setUniform(Uniform("maxDepth", depthCutoff)); combinedProgram->setUniform(Uniform("confThreshold", confThreshold)); combinedProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); combinedProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); combinedProgram->setUniform(Uniform("time", time)); combinedProgram->setUniform(Uniform("maxTime", maxTime)); combinedProgram->setUniform(Uniform("timeDelta", timeDelta)); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, model.second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); if(predictionType == IndexMap::ACTIVE) { combinedFrameBuffer.Unbind(); } else if(predictionType == IndexMap::INACTIVE) { oldFrameBuffer.Unbind(); } else { assert(false); } combinedProgram->Unbind(); glDisable(GL_PROGRAM_POINT_SIZE); glDisable(GL_POINT_SPRITE); glPopAttrib(); glFinish(); } void IndexMap::synthesizeDepth(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold, const int time, const int maxTime, const int timeDelta) { glEnable(GL_PROGRAM_POINT_SIZE); glEnable(GL_POINT_SPRITE); depthFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, depthRenderBuffer.width, depthRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); depthProgram->Bind(); Eigen::Matrix4f t_inv = pose.inverse(); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()); depthProgram->setUniform(Uniform("t_inv", t_inv)); depthProgram->setUniform(Uniform("cam", cam)); depthProgram->setUniform(Uniform("maxDepth", depthCutoff)); depthProgram->setUniform(Uniform("confThreshold", confThreshold)); depthProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); depthProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); depthProgram->setUniform(Uniform("time", time)); depthProgram->setUniform(Uniform("maxTime", maxTime)); depthProgram->setUniform(Uniform("timeDelta", timeDelta)); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, model.second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); depthFrameBuffer.Unbind(); depthProgram->Unbind(); glDisable(GL_PROGRAM_POINT_SIZE); glDisable(GL_POINT_SPRITE); glPopAttrib(); glFinish(); } void IndexMap::synthesizeInfo(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold) { glEnable(GL_PROGRAM_POINT_SIZE); glEnable(GL_POINT_SPRITE); infoFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, infoRenderBuffer.width, infoRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); combinedProgram->Bind(); Eigen::Matrix4f t_inv = pose.inverse(); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), Intrinsics::getInstance().fx(), Intrinsics::getInstance().fy()); combinedProgram->setUniform(Uniform("t_inv", t_inv)); combinedProgram->setUniform(Uniform("cam", cam)); combinedProgram->setUniform(Uniform("maxDepth", depthCutoff)); combinedProgram->setUniform(Uniform("confThreshold", confThreshold)); combinedProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); combinedProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); combinedProgram->setUniform(Uniform("time", 0)); combinedProgram->setUniform(Uniform("maxTime", std::numeric_limits::max())); combinedProgram->setUniform(Uniform("timeDelta", std::numeric_limits::max())); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, model.second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); infoFrameBuffer.Unbind(); combinedProgram->Unbind(); glDisable(GL_PROGRAM_POINT_SIZE); glDisable(GL_POINT_SPRITE); glPopAttrib(); glFinish(); } ================================================ FILE: obj_pose_est/mapping/Core/src/IndexMap.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef INDEXMAP_H_ #define INDEXMAP_H_ #include "Shaders/Shaders.h" #include "Shaders/Uniform.h" #include "Shaders/Vertex.h" #include "GPUTexture.h" #include "Utils/Resolution.h" #include "Utils/Intrinsics.h" #include #include #include "Defines.h" class IndexMap { public: IndexMap(); virtual ~IndexMap(); void predictIndices(const Eigen::Matrix4f & pose, const int & time, const std::pair & model, const float depthCutoff, const int timeDelta); EFUSION_API void renderDepth(const float depthCutoff); enum Prediction { ACTIVE, INACTIVE }; void combinedPredict(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold, const int time, const int maxTime, const int timeDelta, IndexMap::Prediction predictionType); void synthesizeInfo(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold); void synthesizeDepth(const Eigen::Matrix4f & pose, const std::pair & model, const float depthCutoff, const float confThreshold, const int time, const int maxTime, const int timeDelta); GPUTexture * indexTex() { return &indexTexture; } GPUTexture * vertConfTex() { return &vertConfTexture; } GPUTexture * colorTimeTex() { return &colorTimeTexture; } GPUTexture * normalRadTex() { return &normalRadTexture; } GPUTexture * drawTex() { return &drawTexture; } GPUTexture * depthTex() { return &depthTexture; } GPUTexture * imageTex() { return &imageTexture; } GPUTexture * vertexTex() { return &vertexTexture; } GPUTexture * normalTex() { return &normalTexture; } GPUTexture * timeTex() { return &timeTexture; } GPUTexture * oldImageTex() { return &oldImageTexture; } GPUTexture * oldVertexTex() { return &oldVertexTexture; } GPUTexture * oldNormalTex() { return &oldNormalTexture; } GPUTexture * oldTimeTex() { return &oldTimeTexture; } GPUTexture * colorInfoTex() { return &colorInfoTexture; } GPUTexture * vertexInfoTex() { return &vertexInfoTexture; } GPUTexture * normalInfoTex() { return &normalInfoTexture; } static const int FACTOR; private: std::shared_ptr indexProgram; pangolin::GlFramebuffer indexFrameBuffer; pangolin::GlRenderBuffer indexRenderBuffer; GPUTexture indexTexture; GPUTexture vertConfTexture; GPUTexture colorTimeTexture; GPUTexture normalRadTexture; std::shared_ptr drawDepthProgram; pangolin::GlFramebuffer drawFrameBuffer; pangolin::GlRenderBuffer drawRenderBuffer; GPUTexture drawTexture; std::shared_ptr depthProgram; pangolin::GlFramebuffer depthFrameBuffer; pangolin::GlRenderBuffer depthRenderBuffer; GPUTexture depthTexture; std::shared_ptr combinedProgram; pangolin::GlFramebuffer combinedFrameBuffer; pangolin::GlRenderBuffer combinedRenderBuffer; GPUTexture imageTexture; GPUTexture vertexTexture; GPUTexture normalTexture; GPUTexture timeTexture; pangolin::GlFramebuffer oldFrameBuffer; pangolin::GlRenderBuffer oldRenderBuffer; GPUTexture oldImageTexture; GPUTexture oldVertexTexture; GPUTexture oldNormalTexture; GPUTexture oldTimeTexture; pangolin::GlFramebuffer infoFrameBuffer; pangolin::GlRenderBuffer infoRenderBuffer; GPUTexture colorInfoTexture; GPUTexture vertexInfoTexture; GPUTexture normalInfoTexture; }; #endif /* INDEXMAP_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/PoseMatch.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef POSEMATCH_H_ #define POSEMATCH_H_ #include #include "Ferns.h" class PoseMatch { public: PoseMatch(int firstId, int secondId, const Eigen::Matrix4f & first, const Eigen::Matrix4f & second, const std::vector & constraints, const bool & fern) : firstId(firstId), secondId(secondId), first(first), second(second), constraints(constraints), fern(fern) {} int firstId; int secondId; Eigen::Matrix4f first; Eigen::Matrix4f second; std::vector constraints; bool fern; }; #endif /* POSEMATCH_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/ComputePack.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "ComputePack.h" const std::string ComputePack::NORM = "NORM"; const std::string ComputePack::FILTER = "FILTER"; const std::string ComputePack::METRIC = "METRIC"; const std::string ComputePack::METRIC_FILTERED = "METRIC_FILTERED"; ComputePack::ComputePack(std::shared_ptr program, pangolin::GlTexture * target) : program(program), renderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), target(target) { frameBuffer.AttachColour(*target); frameBuffer.AttachDepth(renderBuffer); } ComputePack::~ComputePack() { } void ComputePack::compute(pangolin::GlTexture * input, const std::vector * const uniforms) { input->Bind(); frameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, renderBuffer.width, renderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); program->Bind(); if(uniforms) { for(size_t i = 0; i < uniforms->size(); i++) { program->setUniform(uniforms->at(i)); } } glDrawArrays(GL_POINTS, 0, 1); frameBuffer.Unbind(); program->Unbind(); glPopAttrib(); glFinish(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/ComputePack.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef COMPUTEPACK_H_ #define COMPUTEPACK_H_ #include "Shaders.h" #include "../Utils/Resolution.h" #include "Uniform.h" #include class ComputePack { public: ComputePack(std::shared_ptr program, pangolin::GlTexture * target); virtual ~ComputePack(); static const std::string NORM, FILTER, METRIC, METRIC_FILTERED; void compute(pangolin::GlTexture * input, const std::vector * const uniforms = 0); private: std::shared_ptr program; pangolin::GlRenderBuffer renderBuffer; pangolin::GlTexture * target; pangolin::GlFramebuffer frameBuffer; }; #endif /* COMPUTEPACK_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/FeedbackBuffer.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "FeedbackBuffer.h" const std::string FeedbackBuffer::RAW = "RAW"; const std::string FeedbackBuffer::FILTERED = "FILTERED"; FeedbackBuffer::FeedbackBuffer(std::shared_ptr program) : program(program), drawProgram(loadProgramFromFile("draw_feedback.vert", "draw_feedback.frag")), bufferSize(Resolution::getInstance().numPixels() * Vertex::SIZE), count(0) { float * vertices = new float[bufferSize]; memset(&vertices[0], 0, bufferSize); glGenTransformFeedbacks(1, &fid); glGenBuffers(1, &vbo); glBindBuffer(GL_ARRAY_BUFFER, vbo); glBufferData(GL_ARRAY_BUFFER, bufferSize, &vertices[0], GL_STREAM_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); delete [] vertices; std::vector uv; for(int i = 0; i < Resolution::getInstance().width(); i++) { for(int j = 0; j < Resolution::getInstance().height(); j++) { uv.push_back(Eigen::Vector2f(((float)i / (float)Resolution::getInstance().width()) + 1.0 / (2 * (float)Resolution::getInstance().width()), ((float)j / (float)Resolution::getInstance().height()) + 1.0 / (2 * (float)Resolution::getInstance().height()))); } } glGenBuffers(1, &uvo); glBindBuffer(GL_ARRAY_BUFFER, uvo); glBufferData(GL_ARRAY_BUFFER, uv.size() * sizeof(Eigen::Vector2f), &uv[0], GL_STATIC_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); program->Bind(); int loc[3] = { glGetVaryingLocationNV(program->programId(), "vPosition0"), glGetVaryingLocationNV(program->programId(), "vColor0"), glGetVaryingLocationNV(program->programId(), "vNormRad0"), }; glTransformFeedbackVaryingsNV(program->programId(), 3, loc, GL_INTERLEAVED_ATTRIBS); program->Unbind(); glGenQueries(1, &countQuery); } FeedbackBuffer::~FeedbackBuffer() { glDeleteTransformFeedbacks(1, &fid); glDeleteBuffers(1, &vbo); glDeleteBuffers(1, &uvo); glDeleteQueries(1, &countQuery); } void FeedbackBuffer::compute(pangolin::GlTexture * color, pangolin::GlTexture * depth, const int & time, const float depthCutoff) { program->Bind(); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), 1.0f / Intrinsics::getInstance().fx(), 1.0f / Intrinsics::getInstance().fy()); program->setUniform(Uniform("cam", cam)); program->setUniform(Uniform("threshold", 0.0f)); program->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); program->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); program->setUniform(Uniform("time", time)); program->setUniform(Uniform("gSampler", 0)); program->setUniform(Uniform("cSampler", 1)); program->setUniform(Uniform("maxDepth", depthCutoff)); glEnableVertexAttribArray(0); glBindBuffer(GL_ARRAY_BUFFER, uvo); glVertexAttribPointer(0, 2, GL_FLOAT, GL_FALSE, 0, 0); glEnable(GL_RASTERIZER_DISCARD); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, fid); glBindBufferBase(GL_TRANSFORM_FEEDBACK_BUFFER, 0, vbo); glBeginTransformFeedback(GL_POINTS); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, depth->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, color->tid); glDrawArrays(GL_POINTS, 0, Resolution::getInstance().numPixels()); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); glEndTransformFeedback(); glDisable(GL_RASTERIZER_DISCARD); glDisableVertexAttribArray(0); glBindBuffer(GL_ARRAY_BUFFER, 0); glBindTransformFeedback(GL_TRANSFORM_FEEDBACK, 0); program->Unbind(); glFinish(); } void FeedbackBuffer::render(pangolin::OpenGlMatrix mvp, const Eigen::Matrix4f & pose, const bool drawNormals, const bool drawColors) { drawProgram->Bind(); drawProgram->setUniform(Uniform("MVP", mvp)); drawProgram->setUniform(Uniform("pose", pose)); drawProgram->setUniform(Uniform("colorType", (drawNormals ? 1 : drawColors ? 2 : 0))); glBindBuffer(GL_ARRAY_BUFFER, vbo); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, fid); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); drawProgram->Unbind(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/FeedbackBuffer.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef FEEDBACKBUFFER_H_ #define FEEDBACKBUFFER_H_ #include "Shaders.h" #include "Uniform.h" #include "Vertex.h" #include "../Utils/Resolution.h" #include "../Utils/Intrinsics.h" #include #include #include "../Defines.h" class FeedbackBuffer { public: FeedbackBuffer(std::shared_ptr program); virtual ~FeedbackBuffer(); std::shared_ptr program; void compute(pangolin::GlTexture * color, pangolin::GlTexture * depth, const int & time, const float depthCutoff); EFUSION_API void render(pangolin::OpenGlMatrix mvp, const Eigen::Matrix4f & pose, const bool drawNormals, const bool drawColors); EFUSION_API static const std::string RAW, FILTERED; GLuint vbo; GLuint fid; private: std::shared_ptr drawProgram; GLuint uvo; GLuint countQuery; const int bufferSize; unsigned int count; }; #endif /* FEEDBACKBUFFER_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/FillIn.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "FillIn.h" FillIn::FillIn() : imageTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), vertexTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), normalTexture(Resolution::getInstance().width(), Resolution::getInstance().height(), GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), imageProgram(loadProgramFromFile("empty.vert", "fill_rgb.frag", "quad.geom")), imageRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), vertexProgram(loadProgramFromFile("empty.vert", "fill_vertex.frag", "quad.geom")), vertexRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()), normalProgram(loadProgramFromFile("empty.vert", "fill_normal.frag", "quad.geom")), normalRenderBuffer(Resolution::getInstance().width(), Resolution::getInstance().height()) { imageFrameBuffer.AttachColour(*imageTexture.texture); imageFrameBuffer.AttachDepth(imageRenderBuffer); vertexFrameBuffer.AttachColour(*vertexTexture.texture); vertexFrameBuffer.AttachDepth(vertexRenderBuffer); normalFrameBuffer.AttachColour(*normalTexture.texture); normalFrameBuffer.AttachDepth(normalRenderBuffer); } FillIn::~FillIn() { } void FillIn::image(GPUTexture * existingRgb, GPUTexture * rawRgb, bool passthrough) { imageFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, imageRenderBuffer.width, imageRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); imageProgram->Bind(); imageProgram->setUniform(Uniform("eSampler", 0)); imageProgram->setUniform(Uniform("rSampler", 1)); imageProgram->setUniform(Uniform("passthrough", (int)passthrough)); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, existingRgb->texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, rawRgb->texture->tid); glDrawArrays(GL_POINTS, 0, 1); imageFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); imageProgram->Unbind(); glPopAttrib(); glFinish(); } void FillIn::vertex(GPUTexture * existingVertex, GPUTexture * rawDepth, bool passthrough) { vertexFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, vertexRenderBuffer.width, vertexRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); vertexProgram->Bind(); vertexProgram->setUniform(Uniform("eSampler", 0)); vertexProgram->setUniform(Uniform("rSampler", 1)); vertexProgram->setUniform(Uniform("passthrough", (int)passthrough)); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), 1.0f / Intrinsics::getInstance().fx(), 1.0f / Intrinsics::getInstance().fy()); vertexProgram->setUniform(Uniform("cam", cam)); vertexProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); vertexProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, existingVertex->texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, rawDepth->texture->tid); glDrawArrays(GL_POINTS, 0, 1); vertexFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); vertexProgram->Unbind(); glPopAttrib(); glFinish(); } void FillIn::normal(GPUTexture * existingNormal, GPUTexture * rawDepth, bool passthrough) { normalFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, normalRenderBuffer.width, normalRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); normalProgram->Bind(); normalProgram->setUniform(Uniform("eSampler", 0)); normalProgram->setUniform(Uniform("rSampler", 1)); normalProgram->setUniform(Uniform("passthrough", (int)passthrough)); Eigen::Vector4f cam(Intrinsics::getInstance().cx(), Intrinsics::getInstance().cy(), 1.0f / Intrinsics::getInstance().fx(), 1.0f / Intrinsics::getInstance().fy()); normalProgram->setUniform(Uniform("cam", cam)); normalProgram->setUniform(Uniform("cols", (float)Resolution::getInstance().cols())); normalProgram->setUniform(Uniform("rows", (float)Resolution::getInstance().rows())); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, existingNormal->texture->tid); glActiveTexture(GL_TEXTURE1); glBindTexture(GL_TEXTURE_2D, rawDepth->texture->tid); glDrawArrays(GL_POINTS, 0, 1); normalFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); normalProgram->Unbind(); glPopAttrib(); glFinish(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/FillIn.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef FILLIN_H_ #define FILLIN_H_ #include "Shaders.h" #include "Uniform.h" #include "../Utils/Resolution.h" #include "../Utils/Intrinsics.h" #include "../GPUTexture.h" class FillIn { public: FillIn(); virtual ~FillIn(); void image(GPUTexture * existingRgb, GPUTexture * rawRgb, bool passthrough); void vertex(GPUTexture * existingVertex, GPUTexture * rawDepth, bool passthrough); void normal(GPUTexture * existingNormal, GPUTexture * rawDepth, bool passthrough); GPUTexture imageTexture; GPUTexture vertexTexture; GPUTexture normalTexture; std::shared_ptr imageProgram; pangolin::GlRenderBuffer imageRenderBuffer; pangolin::GlFramebuffer imageFrameBuffer; std::shared_ptr vertexProgram; pangolin::GlRenderBuffer vertexRenderBuffer; pangolin::GlFramebuffer vertexFrameBuffer; std::shared_ptr normalProgram; pangolin::GlRenderBuffer normalRenderBuffer; pangolin::GlFramebuffer normalFrameBuffer; }; #endif /* FILLIN_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Resize.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "Resize.h" Resize::Resize(int srcWidth, int srcHeight, int destWidth, int destHeight) : imageTexture(destWidth, destHeight, GL_RGBA, GL_RGB, GL_UNSIGNED_BYTE, false, true), vertexTexture(destWidth, destHeight, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, false, true), timeTexture(destWidth, destHeight, GL_LUMINANCE16UI_EXT, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT, false, true), imageProgram(loadProgramFromFile("empty.vert", "resize.frag", "quad.geom")), imageRenderBuffer(destWidth, destHeight), vertexProgram(loadProgramFromFile("empty.vert", "resize.frag", "quad.geom")), vertexRenderBuffer(destWidth, destHeight), timeProgram(loadProgramFromFile("empty.vert", "resize.frag", "quad.geom")), timeRenderBuffer(destWidth, destHeight) { imageFrameBuffer.AttachColour(*imageTexture.texture); imageFrameBuffer.AttachDepth(imageRenderBuffer); vertexFrameBuffer.AttachColour(*vertexTexture.texture); vertexFrameBuffer.AttachDepth(vertexRenderBuffer); timeFrameBuffer.AttachColour(*timeTexture.texture); timeFrameBuffer.AttachDepth(timeRenderBuffer); } Resize::~Resize() { } void Resize::image(GPUTexture * source, Img> & dest) { imageFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, imageRenderBuffer.width, imageRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); imageProgram->Bind(); imageProgram->setUniform(Uniform("eSampler", 0)); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, source->texture->tid); glDrawArrays(GL_POINTS, 0, 1); glReadPixels(0, 0, imageRenderBuffer.width, imageRenderBuffer.height, GL_RGB, GL_UNSIGNED_BYTE, dest.data); imageFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); imageProgram->Unbind(); glPopAttrib(); glFinish(); } void Resize::vertex(GPUTexture * source, Img & dest) { vertexFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, vertexRenderBuffer.width, vertexRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); vertexProgram->Bind(); vertexProgram->setUniform(Uniform("eSampler", 0)); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, source->texture->tid); glDrawArrays(GL_POINTS, 0, 1); glReadPixels(0, 0, vertexRenderBuffer.width, vertexRenderBuffer.height, GL_RGBA, GL_FLOAT, dest.data); vertexFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); vertexProgram->Unbind(); glPopAttrib(); glFinish(); } void Resize::time(GPUTexture * source, Img & dest) { timeFrameBuffer.Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, timeRenderBuffer.width, timeRenderBuffer.height); glClearColor(0, 0, 0, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); timeProgram->Bind(); timeProgram->setUniform(Uniform("eSampler", 0)); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, source->texture->tid); glDrawArrays(GL_POINTS, 0, 1); glReadPixels(0, 0, timeRenderBuffer.width, timeRenderBuffer.height, GL_LUMINANCE_INTEGER_EXT, GL_UNSIGNED_SHORT, dest.data); timeFrameBuffer.Unbind(); glBindTexture(GL_TEXTURE_2D, 0); glActiveTexture(GL_TEXTURE0); timeProgram->Unbind(); glPopAttrib(); glFinish(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Resize.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef RESIZE_H_ #define RESIZE_H_ #include "Shaders.h" #include "Uniform.h" #include "../Utils/Resolution.h" #include "../Utils/Intrinsics.h" #include "../GPUTexture.h" #include "../Utils/Img.h" #include "../Defines.h" class Resize { public: EFUSION_API Resize(int srcWidth, int srcHeight, int destWidth, int destHeight); virtual ~Resize(); void image(GPUTexture * source, Img> & dest); void vertex(GPUTexture * source, Img & dest); void time(GPUTexture * source, Img & dest); GPUTexture imageTexture; GPUTexture vertexTexture; GPUTexture timeTexture; std::shared_ptr imageProgram; pangolin::GlRenderBuffer imageRenderBuffer; pangolin::GlFramebuffer imageFrameBuffer; std::shared_ptr vertexProgram; pangolin::GlRenderBuffer vertexRenderBuffer; pangolin::GlFramebuffer vertexFrameBuffer; std::shared_ptr timeProgram; pangolin::GlRenderBuffer timeRenderBuffer; pangolin::GlFramebuffer timeFrameBuffer; }; #endif /* RESIZE_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Shaders.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef SHADERS_SHADERS_H_ #define SHADERS_SHADERS_H_ #include #include #include "../Utils/Parse.h" #include "Uniform.h" class Shader : public pangolin::GlSlProgram { public: Shader() {} GLuint programId() { return prog; } void setUniform(const Uniform & v) { GLuint loc = glGetUniformLocation(prog, v.id.c_str()); switch(v.t) { case Uniform::INT: glUniform1i(loc, v.i); break; case Uniform::FLOAT: glUniform1f(loc, v.f); break; case Uniform::VEC2: glUniform2f(loc, v.v2(0), v.v2(1)); break; case Uniform::VEC3: glUniform3f(loc, v.v3(0), v.v3(1), v.v3(2)); break; case Uniform::VEC4: glUniform4f(loc, v.v4(0), v.v4(1), v.v4(2), v.v4(3)); break; case Uniform::MAT4: glUniformMatrix4fv(loc, 1, false, v.m4.data()); break; default: assert(false && "Uniform type not implemented!"); break; } } }; static inline std::shared_ptr loadProgramGeomFromFile(const std::string& vertex_shader_file, const std::string& geometry_shader_file) { std::shared_ptr program = std::make_shared(); program->AddShaderFromFile(pangolin::GlSlVertexShader, Parse::get().shaderDir() + "/" + vertex_shader_file, {}, {Parse::get().shaderDir()}); program->AddShaderFromFile(pangolin::GlSlGeometryShader, Parse::get().shaderDir() + "/" + geometry_shader_file, {}, {Parse::get().shaderDir()}); program->Link(); return program; } static inline std::shared_ptr loadProgramFromFile(const std::string& vertex_shader_file) { std::shared_ptr program = std::make_shared(); program->AddShaderFromFile(pangolin::GlSlVertexShader, Parse::get().shaderDir() + "/" + vertex_shader_file, {}, {Parse::get().shaderDir()}); program->Link(); return program; } static inline std::shared_ptr loadProgramFromFile(const std::string& vertex_shader_file, const std::string& fragment_shader_file) { std::shared_ptr program = std::make_shared(); program->AddShaderFromFile(pangolin::GlSlVertexShader, Parse::get().shaderDir() + "/" + vertex_shader_file, {}, {Parse::get().shaderDir()}); program->AddShaderFromFile(pangolin::GlSlFragmentShader, Parse::get().shaderDir() + "/" + fragment_shader_file, {}, {Parse::get().shaderDir()}); program->Link(); return program; } static inline std::shared_ptr loadProgramFromFile(const std::string& vertex_shader_file, const std::string& fragment_shader_file, const std::string& geometry_shader_file) { std::shared_ptr program = std::make_shared(); program->AddShaderFromFile(pangolin::GlSlVertexShader, Parse::get().shaderDir() + "/" + vertex_shader_file, {}, {Parse::get().shaderDir()}); program->AddShaderFromFile(pangolin::GlSlGeometryShader, Parse::get().shaderDir() + "/" + geometry_shader_file, {}, {Parse::get().shaderDir()}); program->AddShaderFromFile(pangolin::GlSlFragmentShader, Parse::get().shaderDir() + "/" + fragment_shader_file, {}, {Parse::get().shaderDir()}); program->Link(); return program; } #endif /* SHADERS_SHADERS_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Uniform.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef UNIFORM_H_ #define UNIFORM_H_ #include #include class Uniform { public: Uniform(const std::string & id, const int & v) : id(id), i(v), t(INT) {} Uniform(const std::string & id, const float & v) : id(id), f(v), t(FLOAT) {} Uniform(const std::string & id, const Eigen::Vector2f & v) : id(id), v2(v), t(VEC2) {} Uniform(const std::string & id, const Eigen::Vector3f & v) : id(id), v3(v), t(VEC3) {} Uniform(const std::string & id, const Eigen::Vector4f & v) : id(id), v4(v), t(VEC4) {} Uniform(const std::string & id, const Eigen::Matrix4f & v) : id(id), m4(v), t(MAT4) {} std::string id; int i; float f; Eigen::Vector2f v2; Eigen::Vector3f v3; Eigen::Vector4f v4; Eigen::Matrix4f m4; enum Type { INT, FLOAT, VEC2, VEC3, VEC4, MAT4, NONE }; Type t; }; #endif /* UNIFORM_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Vertex.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "Vertex.h" /* * OK this is the structure * *-------------------- * vec3 position * float confidence * * float color (encoded as a 24-bit integer) * float * float initTime * float timestamp * * vec3 normal * float radius *-------------------- * Which is three vec4s */ const int Vertex::SIZE = sizeof(Eigen::Vector4f) * 3; ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/Vertex.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef VERTEX_H_ #define VERTEX_H_ #include #include "../Defines.h" class Vertex { public: EFUSION_API static const int SIZE; private: Vertex(){} }; #endif /* VERTEX_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/color.glsl ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ float encodeColor(vec3 c) { int rgb = int(round(c.x * 255.0f)); rgb = (rgb << 8) + int(round(c.y * 255.0f)); rgb = (rgb << 8) + int(round(c.z * 255.0f)); return float(rgb); } vec3 decodeColor(float c) { vec3 col; col.x = float(int(c) >> 16 & 0xFF) / 255.0f; col.y = float(int(c) >> 8 & 0xFF) / 255.0f; col.z = float(int(c) & 0xFF) / 255.0f; return col; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/combo_splat.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core uniform vec4 cam; //cx, cy, fx, fy uniform float maxDepth; in vec4 position; in vec4 normRad; in vec4 colTime; layout(location = 0) out vec4 image; layout(location = 1) out vec4 vertex; layout(location = 2) out vec4 normal; layout(location = 3) out uint time; #include "color.glsl" void main() { vec3 l = normalize(vec3((vec2(gl_FragCoord) - cam.xy) / cam.zw, 1.0f)); vec3 corrected_pos = (dot(position.xyz, normRad.xyz) / dot(l, normRad.xyz)) * l; //check if the intersection is inside the surfel float sqrRad = pow(normRad.w, 2); vec3 diff = corrected_pos - position.xyz; if(dot(diff, diff) > sqrRad) { discard; } image = vec4(decodeColor(colTime.x), 1); float z = corrected_pos.z; vertex = vec4((gl_FragCoord.x - cam.x) * z * (1.f / cam.z), (gl_FragCoord.y - cam.y) * z * (1.f / cam.w), z, position.w); normal = normRad; time = uint(colTime.z); gl_FragDepth = (corrected_pos.z / (2 * maxDepth)) + 0.5f; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/copy_unstable.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(points, max_vertices = 1) out; in vec4 vPosition[]; in vec4 vColor[]; in vec4 vNormRad[]; flat in int test[]; out vec4 vPosition0; out vec4 vColor0; out vec4 vNormRad0; void main() { if(test[0] > 0) { vPosition0 = vPosition[0]; vColor0 = vColor[0]; vNormRad0 = vNormRad[0]; EmitVertex(); EndPrimitive(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/copy_unstable.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPos; layout (location = 1) in vec4 vCol; layout (location = 2) in vec4 vNormR; out vec4 vPosition; out vec4 vColor; out vec4 vNormRad; flat out int test; uniform int time; uniform float scale; uniform mat4 t_inv; uniform vec4 cam; //cx, cy, fx, fy uniform float cols; uniform float rows; uniform float confThreshold; uniform usampler2D indexSampler; uniform sampler2D vertConfSampler; uniform sampler2D colorTimeSampler; uniform sampler2D normRadSampler; uniform sampler2D nodeSampler; uniform sampler2D depthSampler; uniform float nodes; uniform float nodeCols; uniform float maxDepth; uniform int timeDelta; uniform int isFern; void main() { vPosition = vPos; vColor = vCol; vNormRad = vNormR; test = 1; vec3 localPos = (t_inv * vec4(vPosition.xyz, 1.0f)).xyz; float x = ((cam.z * localPos.x) / localPos.z) + cam.x; float y = ((cam.w * localPos.y) / localPos.z) + cam.y; vec3 localNorm = normalize(mat3(t_inv) * vNormRad.xyz); float indexXStep = (1.0f / (cols * scale)) * 0.5f; float indexYStep = (1.0f / (rows * scale)) * 0.5f; float windowMultiplier = 2; int count = 0; int zCount = 0; if(//abs(localNorm.z) > 0.85f && time - vColor.w < timeDelta && localPos.z > 0 && x > 0 && y > 0 && x < cols && y < rows) { for(float i = x / cols - (scale * indexXStep * windowMultiplier); i < x / cols + (scale * indexXStep * windowMultiplier); i += indexXStep) { for(float j = y / rows - (scale * indexYStep * windowMultiplier); j < y / rows + (scale * indexYStep * windowMultiplier); j += indexYStep) { uint current = uint(textureLod(indexSampler, vec2(i, j), 0)); if(current > 0U) { vec4 vertConf = textureLod(vertConfSampler, vec2(i, j), 0); vec4 colorTime = textureLod(colorTimeSampler, vec2(i, j), 0); if(colorTime.z < vColor.z && vertConf.w > confThreshold && vertConf.z > localPos.z && vertConf.z - localPos.z < 0.01 && sqrt(dot(vertConf.xy - localPos.xy, vertConf.xy - localPos.xy)) < vNormRad.w * 1.4) { count++; } if(colorTime.w == time && vertConf.w > confThreshold && vertConf.z > localPos.z && vertConf.z - localPos.z > 0.01 && abs(localNorm.z) > 0.85f) { zCount++; } } } } } if(count > 8 || zCount > 4) { test = 0; } //New unstable point if(vColor.w == -2) { vColor.w = time; } //Degenerate case or too unstable if((vColor.w == -1 || ((time - vColor.w) > 20 && vPosition.w < confThreshold))) { test = 0; } if(vColor.w > 0 && time - vColor.w > timeDelta) { test = 1; } //This is probably really slow //We don't deform vColor.z == time because they were fused with the updated pose already! if(test == 1 && nodes > 0 && vColor.z != time) { const int k = 4; const int lookBack = 20; int nearNodes[lookBack]; float nearDists[lookBack]; for(int i = 0; i < lookBack; i++) { nearNodes[i] = -1; nearDists[i] = 16777216.0f; } int poseTime = int(vColor.z); int foundIndex = 0; int imin = 0; int imax = int(nodes) - 1; int imid = (imin + imax) / 2; while(imax >= imin) { imid = (imin + imax) / 2; int nodeTime = int(textureLod(nodeSampler, vec2(((imid * 16 + 15) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); if(nodeTime < poseTime) { imin = imid + 1; } else if(nodeTime > poseTime) { imax = imid - 1; } else { break; } } imin = min(imin, int(nodes) - 1); int nodeMin = int(textureLod(nodeSampler, vec2(((imin * 16 + 15) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); int nodeMid = int(textureLod(nodeSampler, vec2(((imid * 16 + 15) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); int nodeMax = int(textureLod(nodeSampler, vec2(((imax * 16 + 15) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); if(abs(nodeMin - poseTime) <= abs(nodeMid - poseTime) && abs(nodeMin - poseTime) <= abs(nodeMax - poseTime)) { foundIndex = imin; } else if(abs(nodeMid - poseTime) <= abs(nodeMin - poseTime) && abs(nodeMid - poseTime) <= abs(nodeMax - poseTime)) { foundIndex = imid; } else { foundIndex = imax; } if(foundIndex == int(nodes)) { foundIndex = int(nodes) - 1; } int nearNodeIndex = 0; int distanceBack = 0; for(int j = foundIndex; j >= 0; j--) { vec3 position = vec3(textureLod(nodeSampler, vec2(((j * 16) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((j * 16 + 1) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((j * 16 + 2) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); nearNodes[nearNodeIndex] = j; nearDists[nearNodeIndex] = sqrt(dot(vPosition.xyz - position, vPosition.xyz - position)); nearNodeIndex++; if(++distanceBack == lookBack / 2) { break; } } for(int j = foundIndex + 1; j < int(nodes); j++) { vec3 position = vec3(textureLod(nodeSampler, vec2(((j * 16) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((j * 16 + 1) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((j * 16 + 2) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); nearNodes[nearNodeIndex] = j; nearDists[nearNodeIndex] = sqrt(dot(vPosition.xyz - position, vPosition.xyz - position)); nearNodeIndex++; if(++distanceBack == lookBack) { break; } } for(int i = 0; i < lookBack - 1; ++i) { for(int j = i + 1; j < lookBack; ++j) { if(nearDists[j] < nearDists[i]) { float t = nearDists[i]; nearDists[i] = nearDists[j]; nearDists[j] = t; int t2 = nearNodes[i]; nearNodes[i] = nearNodes[j]; nearNodes[j] = t2; } } } float dMax = nearDists[k]; float nodeWeights[k]; float weightSum = 0; for(int j = 0; j < k; j++) { vec3 position = vec3(textureLod(nodeSampler, vec2(((nearNodes[j] * 16) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[j] * 16 + 1) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[j] * 16 + 2) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); nodeWeights[j] = pow(1.0f - (sqrt(dot(vPosition.xyz - position, vPosition.xyz - position)) / dMax), 2); weightSum += nodeWeights[j]; } for(int j = 0; j < k; j++) { nodeWeights[j] /= weightSum; } vec3 newPos = vec3(0, 0, 0); vec3 newNorm = vec3(0, 0, 0); for(int i = 0; i < k; i++) { vec3 position = vec3(textureLod(nodeSampler, vec2(((nearNodes[i] * 16) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 1) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 2) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); vec3 column0 = vec3(textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 3) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 4) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 5) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); vec3 column1 = vec3(textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 6) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 7) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 8) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); vec3 column2 = vec3(textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 9) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 10) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 11) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); mat3 rotation = mat3(column0, column1, column2); vec3 translation = vec3(textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 12) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 13) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x, textureLod(nodeSampler, vec2(((nearNodes[i] * 16 + 14) / nodeCols) + (1.0 / (nodeCols * 2)), 0.5), 0).x); newPos += nodeWeights[i] * (rotation * (vPosition.xyz - position) + position + translation); newNorm += nodeWeights[i] * (transpose(inverse(rotation)) * vNormRad.xyz); } vPosition.xyz = newPos; vNormRad.xyz = normalize(newNorm); if(vPosition.w > confThreshold && isFern == 0) { localPos = (t_inv * vec4(vPosition.xyz, 1.0f)).xyz; x = ((cam.z * localPos.x) / localPos.z) + cam.x; y = ((cam.w * localPos.y) / localPos.z) + cam.y; if(localPos.z > 0 && localPos.z < maxDepth && x > 0 && y > 0 && x < cols && y < rows) { float currentDepth = float(textureLod(depthSampler, vec2(x / cols, y / rows), 0)); if(currentDepth > 0.0f && localPos.z < currentDepth + 0.1f) { vColor.w = time; } } } } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/data.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec4 vPosition0; in vec4 vColor0; in vec4 vNormRad0; flat in int updateId0; layout(location = 0) out vec4 vPosition1; layout(location = 1) out vec4 vColor1; layout(location = 2) out vec4 vNormRad1; void main() { //If we have a point to update in the existing model, store that if(updateId0 == 1) { vPosition1 = vPosition0; vColor1 = vColor0; vNormRad1 = vNormRad0; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/data.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(points, max_vertices = 1) out; in vec4 vPosition[]; in vec4 vColor[]; in vec4 vNormRad[]; flat in int updateId[]; out vec4 vPosition0; out vec4 vColor0; out vec4 vNormRad0; flat out int updateId0; void main() { //Emit a vertex if either we have an update to store, or a new unstable vertex to store if(updateId[0] > 0) { vPosition0 = vPosition[0]; vColor0 = vColor[0]; vNormRad0 = vNormRad[0]; updateId0 = updateId[0]; //This will be -10, -10 (offscreen) for new unstable vertices, so they don't show in the fragment shader gl_Position = gl_in[0].gl_Position; EmitVertex(); EndPrimitive(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/data.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec2 texcoord; out vec4 vPosition; out vec4 vColor; out vec4 vNormRad; flat out int updateId; uniform sampler2D cSampler; uniform sampler2D drSampler; uniform sampler2D drfSampler; uniform usampler2D indexSampler; uniform sampler2D vertConfSampler; uniform sampler2D colorTimeSampler; uniform sampler2D normRadSampler; uniform vec4 cam; //cx, cy, 1/fx, 1/fy uniform float cols; uniform float rows; uniform float scale; uniform float texDim; uniform mat4 pose; uniform float maxDepth; uniform float time; uniform float weighting; #include "surfels.glsl" #include "color.glsl" #include "geometry.glsl" bool checkNeighbours(vec2 texCoord, sampler2D depth) { float z = float(textureLod(depth, vec2(texCoord.x - (1.0 / cols), texCoord.y), 0.0)); if(z == 0) return false; z = float(textureLod(depth, vec2(texCoord.x, texCoord.y - (1.0 / rows)), 0.0)); if(z == 0) return false; z = float(textureLod(depth, vec2(texCoord.x + (1.0 / cols), texCoord.y), 0.0)); if(z == 0) return false; z = float(textureLod(depth, vec2(texCoord.x, texCoord.y + (1.0 / rows)), 0.0)); if(z == 0) return false; return true; } float angleBetween(vec3 a, vec3 b) { return acos(dot(a, b) / (length(a) * length(b))); } void main() { //Should be guaranteed to be in bounds and centred on pixels float x = texcoord.x * cols; float y = texcoord.y * rows; //Vertex position integrated into model transformed to global coords vec3 vPosLocal = getVertex(texcoord.xy, x, y, cam, drSampler); vPosition = pose * vec4(vPosLocal, 1); //Filtered position ONLY used for normal and radius calculation vec3 vPosition_f = getVertex(texcoord.xy, x, y, cam, drfSampler); //Color for color, obviously vColor = textureLod(cSampler, texcoord.xy, 0.0); //cuong vec3 vColor_cuong = vColor.xyz; vColor.x = encodeColor(vColor.xyz); vColor.y = 0; vColor.z = time; //Normal and radius computed with filtered position / depth map transformed to global coords vec3 vNormLocal = getNormal(vPosition_f, texcoord.xy, x, y, cam, drfSampler); vNormRad = vec4(mat3(pose) * vNormLocal, getRadius(vPosition_f.z, vNormLocal.z)); //Confidence vPosition.w = confidence(x, y, weighting); //Timestamp //We update this in update.vert, because it's used to signal new points later on vColor.w = 0; updateId = 0; uint best = 0U; //If this point is actually a valid vertex (i.e. has depth) //cuong if(vColor_cuong.x != 0 || vColor_cuong.y != 0 || vColor_cuong.z != 0) if(int(x) % 2 == int(time) % 2 && int(y) % 2 == int(time) % 2 && checkNeighbours(texcoord.xy, drSampler) && vPosLocal.z > 0 && vPosLocal.z <= maxDepth) { int counter = 0; float indexXStep = (1.0f / (cols * scale)) * 0.5f; float indexYStep = (1.0f / (rows * scale)) * 0.5f; float bestDist = 1000; float windowMultiplier = 2; float xl = (x - cam.x) * cam.z; float yl = (y - cam.y) * cam.w; float lambda = sqrt(xl * xl + yl * yl + 1); vec3 ray = vec3(xl, yl, 1); for(float i = texcoord.x - (scale * indexXStep * windowMultiplier); i < texcoord.x + (scale * indexXStep * windowMultiplier); i += indexXStep) { for(float j = texcoord.y - (scale * indexYStep * windowMultiplier); j < texcoord.y + (scale * indexYStep * windowMultiplier); j += indexYStep) { uint current = uint(textureLod(indexSampler, vec2(i, j), 0.0)); if(current > 0U) { vec4 vertConf = textureLod(vertConfSampler, vec2(i, j), 0.0); if(abs((vertConf.z * lambda) - (vPosLocal.z * lambda)) < 0.05) { float dist = length(cross(ray, vertConf.xyz)) / length(ray); vec4 normRad = textureLod(normRadSampler, vec2(i, j), 0.0); if(dist < bestDist && (abs(normRad.z) < 0.75f || abs(angleBetween(normRad.xyz, vNormLocal.xyz)) < 0.5f)) { counter++; bestDist = dist; best = current; } } } } } //We found a point to merge with if(counter > 0) { updateId = 1; vColor.w = -1; } else { //New unstable vertex updateId = 2; vColor.w = -2; } } //Output vertex id of the existing point to update if(updateId == 1) { uint intY = best / uint(texDim); uint intX = best - (intY * uint(texDim)); float halfPixel = 0.5 * (1.0f / texDim); //should set gl_Position here to the 2D index for the updated vertex ID gl_Position = vec4(float(int(intX) - (int(texDim) / 2)) / (texDim / 2.0) + halfPixel, float(int(intY) - (int(texDim) / 2)) / (texDim / 2.0) + halfPixel, 0, 1.0); } else { //Either don't render anything, or output a new unstable vertex offscreen gl_Position = vec4(-10, -10, 0, 1); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/depth_bilateral.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out uint FragColor; uniform usampler2D gSampler; uniform float cols; uniform float rows; uniform float maxD; void main() { uint value = uint(texture(gSampler, texcoord.xy)); if(value > uint(maxD * 1000.0f) || value < 300U) { FragColor = 0U; } else { int x = int(texcoord.x * cols); int y = int(texcoord.y * rows); const float sigma_space2_inv_half = 0.024691358; // 0.5 / (sigma_space * sigma_space) const float sigma_color2_inv_half = 0.000555556; // 0.5 / (sigma_color * sigma_color) const int R = 6; const int D = R * 2 + 1; int tx = min(x - D / 2 + D, int(cols)); int ty = min(y - D / 2 + D, int(rows)); float sum1 = 0; float sum2 = 0; for(int cy = max(y - D / 2, 0); cy < ty; ++cy) { for(int cx = max(x - D / 2, 0); cx < tx; ++cx) { float texX = float(cx) / cols; float texY = float(cy) / rows; uint tmp = uint(texture(gSampler, vec2(texX, texY))); float space2 = (float(x) - float(cx)) * (float(x) - float(cx)) + (float(y) - float(cy)) * (float(y) - float(cy)); float color2 = (float(value) - float(tmp)) * (float(value) - float(tmp)); float weight = exp(-(space2 * sigma_space2_inv_half + color2 * sigma_color2_inv_half)); sum1 += float(tmp) * weight; sum2 += weight; } } FragColor = uint(round(sum1/sum2)); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/depth_metric.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out float FragColor; uniform usampler2D gSampler; uniform float maxD; void main() { uint value = uint(texture(gSampler, texcoord.xy)); if(value > uint(maxD * 1000.0f) || value < 300U) { FragColor = 0U; } else { FragColor = float(value) / 1000.0f; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/depth_norm.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out float FragColor; uniform usampler2D gSampler; uniform float minVal; uniform float maxVal; void main() { uint value = uint(texture(gSampler, texcoord.xy)); if(value > uint(minVal) && value < uint(maxVal)) FragColor = 1.0f - (value / maxVal); else FragColor = 0; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/depth_splat.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core uniform vec4 cam; //cx, cy, fx, fy uniform float maxDepth; in vec4 position; in vec4 normRad; out float FragColor; void main() { vec3 l = normalize(vec3((vec2(gl_FragCoord) - cam.xy) / cam.zw, 1.0f)); vec3 corrected_pos = (dot(position.xyz, normRad.xyz) / dot(l, normRad.xyz)) * l; //check if the intersection is inside the surfel float sqrRad = pow(normRad.w, 2); vec3 diff = corrected_pos - position.xyz; if(dot(diff, diff) > sqrRad) { discard; } FragColor = corrected_pos.z; gl_FragDepth = (corrected_pos.z / (2 * maxDepth)) + 0.5f; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_feedback.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec4 vColor; out vec4 FragColor; void main() { FragColor = vColor; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_feedback.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 position; layout (location = 1) in vec4 color; layout (location = 2) in vec4 normal; uniform mat4 MVP; uniform mat4 pose; uniform float threshold; uniform int colorType; out vec4 vColor; #include "color.glsl" void main() { if(position.w > threshold) { if(colorType == 1) { vColor = vec4(normal.xyz, 1.0); } else if(colorType == 2) { vColor = vec4(decodeColor(color.x), 1.0); } else { vColor = vec4((vec3(.5f, .5f, .5f) * abs(dot(normal.xyz, vec3(1.0, 1.0, 1.0)))) + vec3(0.1f, 0.1f, 0.1f), 1.0f); } gl_Position = MVP * pose * vec4(position.xyz, 1.0); } else { gl_Position = vec4(-10, -10, 0, 1); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_global_surface.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec3 vColor0; in vec2 texcoord; in float radius; flat in int unstablePoint; out vec4 FragColor; void main() { if(dot(texcoord, texcoord) > 1.0) discard; FragColor = vec4(vColor0, 1.0f); if(unstablePoint == 1) { gl_FragDepth = gl_FragCoord.z + radius; } else { gl_FragDepth = gl_FragCoord.z; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_global_surface.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(triangle_strip, max_vertices = 4) out; uniform float threshold; uniform float signMult; in vec4 vColor[]; in vec4 vPosition[]; in vec4 vNormRad[]; in mat4 vMVP[]; in int colorType0[]; in int drawWindow0[]; in int vTime[]; in int timeDelta0[]; out vec3 vColor0; out vec3 v; out vec3 n; out vec2 texcoord; out float radius; flat out int unstablePoint; #include "color.glsl" void main() { if(colorType0[0] != -1) { if(colorType0[0] == 1) { vColor0 = vNormRad[0].xyz; } else if(colorType0[0] == 2) { vColor0 = decodeColor(vColor[0].x); } else if(colorType0[0] == 3) { vColor0 = vec3(vColor[0].z / float(vTime[0])); float minimum = 1.0f; float maximum = float(vTime[0]); float ratio = 2 * (vColor[0].z - minimum) / (maximum - minimum); vColor0.x = max(0, (1 - ratio)); vColor0.y = max(0, (ratio - 1)); vColor0.z = 1.0f - vColor0.x - vColor0.y; vColor0.xyz *= abs(dot(vNormRad[0].xyz, vec3(1.0, 1.0, 1.0))) + vec3(0.1f, 0.1f, 0.1f); } else { vColor0 = (vec3(.5f, .5f, .5f) * abs(dot(vNormRad[0].xyz, vec3(1.0, 1.0, 1.0)))) + vec3(0.1f, 0.1f, 0.1f); } if(drawWindow0[0] == 1 && vTime[0] - vColor[0].w > timeDelta0[0]) { vColor0 *= 0.25; } unstablePoint = (vPosition[0].w <= threshold ? 1 : 0); radius = vNormRad[0].w; vec3 x = normalize(vec3((vNormRad[0].y - vNormRad[0].z), -vNormRad[0].x, vNormRad[0].x)) * vNormRad[0].w * 1.41421356; vec3 y = cross(vNormRad[0].xyz, x); n = signMult * vNormRad[0].xyz; texcoord = vec2(-1.0, -1.0); gl_Position = vMVP[0] * vec4(vPosition[0].xyz + x, 1.0); v = vPosition[0].xyz + x; EmitVertex(); texcoord = vec2(1.0, -1.0); gl_Position = vMVP[0] * vec4(vPosition[0].xyz + y, 1.0); v = vPosition[0].xyz + y; EmitVertex(); texcoord = vec2(-1.0, 1.0); gl_Position = vMVP[0] * vec4(vPosition[0].xyz - y, 1.0); v = vPosition[0].xyz - y; EmitVertex(); texcoord = vec2(1.0, 1.0); gl_Position = vMVP[0] * vec4(vPosition[0].xyz - x, 1.0); v = vPosition[0].xyz - x; EmitVertex(); EndPrimitive(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_global_surface.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 position; layout (location = 1) in vec4 color; layout (location = 2) in vec4 normal; uniform mat4 MVP; uniform float threshold; uniform int colorType; uniform int unstable; uniform int drawWindow; uniform int time; uniform int timeDelta; out vec4 vColor; out vec4 vPosition; out vec4 vNormRad; out mat4 vMVP; out int vTime; out int colorType0; out int drawWindow0; out int timeDelta0; void main() { if(position.w > threshold || unstable == 1) { colorType0 = colorType; drawWindow0 = drawWindow; vColor = color; vPosition = position; vNormRad = normal; vMVP = MVP; vTime = time; timeDelta0 = timeDelta; gl_Position = MVP * vec4(position.xyz, 1.0); } else { colorType0 = -1; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/draw_global_surface_phong.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec3 n; in vec3 v; in vec3 vColor0; in vec2 texcoord; in float radius; flat in int unstablePoint; out vec4 FragColor; uniform vec3 lightpos; void main() { if(dot(texcoord, texcoord) > 1.0) discard; vec4 diffuse = vec4(0.0); vec4 specular = vec4(0.0); // ambient term vec4 ambient = vec4(0.3 * vColor0, 1); // diffuse color vec4 kd = vec4(vColor0, 1.0); // specular color vec4 ks = vec4(1.0, 1.0, 1.0, 1.0); // diffuse term vec3 lightDir = normalize(lightpos - v); float NdotL = dot(n, lightDir); if (NdotL > 0.0) diffuse = kd * NdotL; // specular term vec3 rVector = normalize(2.0 * n * dot(n, lightDir) - lightDir); vec3 viewVector = normalize(-v); float RdotV = dot(rVector, viewVector); if (RdotV > 0.0) specular = ks * pow(RdotV, 32); FragColor = ambient + diffuse + specular; if(unstablePoint == 1) { gl_FragDepth = gl_FragCoord.z + radius; } else { gl_FragDepth = gl_FragCoord.z; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/empty.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 void main() { } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/fill_normal.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out vec4 FragColor; uniform sampler2D eSampler; uniform usampler2D rSampler; uniform vec4 cam; //cx, cy, 1/fx, 1/fy uniform float cols; uniform float rows; uniform int passthrough; #include "geometry.glsl" void main() { float halfPixX = 0.5 * (1.0 / cols); float halfPixY = 0.5 * (1.0 / rows); vec4 sample = textureLod(eSampler, texcoord, 0.0); if(sample.z == 0 || passthrough == 1) { vec4 vPos = vec4(getVertex(texcoord, int(texcoord.x * cols), int(texcoord.y * rows), cam, rSampler), 1); FragColor = vec4(getNormal(vPos.xyz, texcoord, int(texcoord.x * cols), int(texcoord.y * rows), cam, rSampler), 1); } else { FragColor = sample; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/fill_rgb.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out vec4 FragColor; uniform sampler2D eSampler; uniform sampler2D rSampler; uniform int passthrough; void main() { vec4 sample = texture2D(eSampler, texcoord.xy); if(sample.x + sample.y + sample.z == 0 || passthrough == 1) FragColor = texture2D(rSampler, texcoord.xy); else FragColor = sample; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/fill_vertex.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out vec4 FragColor; uniform sampler2D eSampler; uniform usampler2D rSampler; uniform vec4 cam; //cx, cy, 1/fx, 1/fy uniform float cols; uniform float rows; uniform int passthrough; vec3 getVertex(int x, int y, float z) { return vec3((x - cam.x) * z * cam.z, (y - cam.y) * z * cam.w, z); } void main() { float halfPixX = 0.5 * (1.0 / cols); float halfPixY = 0.5 * (1.0 / rows); vec4 sample = textureLod(eSampler, texcoord, 0.0); if(sample.z == 0 || passthrough == 1) { float z = float(textureLod(rSampler, texcoord, 0.0)) / 1000.0f; FragColor = vec4(getVertex(int(texcoord.x * cols), int(texcoord.y * rows), z), 1); } else { FragColor = sample; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/fxaa.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core #define FXAA_REDUCE_MIN (1.0/ 128.0) #define FXAA_REDUCE_MUL (1.0 / 8.0) #define FXAA_SPAN_MAX 8.0 uniform sampler2D tex; uniform vec2 resolution; in vec2 texcoord; out vec4 FragColor; void main() { vec4 color; vec2 inverseVP = 1.0 / resolution.xy; vec2 v_rgbNW = texcoord + (vec2(-1.0, -1.0) * inverseVP); vec2 v_rgbNE = texcoord + (vec2(1.0, -1.0) * inverseVP); vec2 v_rgbSW = texcoord + (vec2(-1.0, 1.0) * inverseVP); vec2 v_rgbSE = texcoord + (vec2(1.0, 1.0) * inverseVP); vec2 v_rgbN = texcoord + (vec2(-1.0, 0.0) * inverseVP); vec2 v_rgbE = texcoord + (vec2(1.0, 0.0) * inverseVP); vec2 v_rgbW = texcoord + (vec2(0.0, -1.0) * inverseVP); vec2 v_rgbS = texcoord + (vec2(0.0, 1.0) * inverseVP); vec2 v_rgbM = texcoord; vec3 rgbNW = texture2D(tex, v_rgbNW).xyz; vec3 rgbNE = texture2D(tex, v_rgbNE).xyz; vec3 rgbSW = texture2D(tex, v_rgbSW).xyz; vec3 rgbSE = texture2D(tex, v_rgbSE).xyz; vec3 rgbN = texture2D(tex, v_rgbN).xyz; vec3 rgbE = texture2D(tex, v_rgbE).xyz; vec3 rgbW = texture2D(tex, v_rgbW).xyz; vec3 rgbS = texture2D(tex, v_rgbS).xyz; vec3 rgbM = texture2D(tex, v_rgbM).xyz; vec3 luma = vec3(0.299, 0.587, 0.114); float lumaNW = dot(rgbNW, luma); float lumaNE = dot(rgbNE, luma); float lumaSW = dot(rgbSW, luma); float lumaSE = dot(rgbSE, luma); float lumaM = dot(rgbM, luma); float lumaMin = min(lumaM, min(min(lumaNW, lumaNE), min(lumaSW, lumaSE))); float lumaMax = max(lumaM, max(max(lumaNW, lumaNE), max(lumaSW, lumaSE))); vec2 dir; dir.x = -((lumaNW + lumaNE) - (lumaSW + lumaSE)); dir.y = ((lumaNW + lumaSW) - (lumaNE + lumaSE)); float dirReduce = max((lumaNW + lumaNE + lumaSW + lumaSE) * (0.25 * FXAA_REDUCE_MUL), FXAA_REDUCE_MIN); float rcpDirMin = 1.0 / (min(abs(dir.x), abs(dir.y)) + dirReduce); dir = min(vec2(FXAA_SPAN_MAX, FXAA_SPAN_MAX), max(vec2(-FXAA_SPAN_MAX, -FXAA_SPAN_MAX), dir * rcpDirMin)) * inverseVP; vec3 rgbA = 0.5 * (texture2D(tex, texcoord + dir * (1.0 / 3.0 - 0.5)).xyz + texture2D(tex, texcoord + dir * (2.0 / 3.0 - 0.5)).xyz); vec3 rgbB = rgbA * 0.5 + 0.25 * (texture2D(tex, texcoord + dir * -0.5).xyz + texture2D(tex, texcoord + dir * 0.5).xyz); float lumaB = dot(rgbB, luma); if ((lumaB < lumaMin) || (lumaB > lumaMax)) FragColor = vec4(rgbA, 1); else FragColor = vec4(rgbB, 1); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/geometry.glsl ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ //Central difference on floating point depth maps //Cam is //cx, cy, 1 / fx, 1 / fy vec3 getVertex(vec2 texCoord, float x, float y, vec4 cam, sampler2D depth) { float z = float(textureLod(depth, texCoord, 0.0)); return vec3((x - cam.x) * z * cam.z, (y - cam.y) * z * cam.w, z); } //Cam is //cx, cy, 1 / fx, 1 / fy vec3 getNormal(vec3 vPosition, vec2 texCoord, float x, float y, vec4 cam, sampler2D depth) { vec3 vPosition_xf = getVertex(vec2(texCoord.x + (1.0 / cols), texCoord.y), x + 1, y, cam, depth); vec3 vPosition_xb = getVertex(vec2(texCoord.x - (1.0 / cols), texCoord.y), x - 1, y, cam, depth); vec3 vPosition_yf = getVertex(vec2(texCoord.x, texCoord.y + (1.0 / rows)), x, y + 1, cam, depth); vec3 vPosition_yb = getVertex(vec2(texCoord.x, texCoord.y - (1.0 / rows)), x, y - 1, cam, depth); vec3 del_x = ((vPosition_xb + vPosition) / 2) - ((vPosition_xf + vPosition) / 2); vec3 del_y = ((vPosition_yb + vPosition) / 2) - ((vPosition_yf + vPosition) / 2); return normalize(cross(del_x, del_y)); } //Forward difference on raw depth maps still in ushort mm //Cam is //cx, cy, 1 / fx, 1 / fy vec3 getVertex(vec2 texcoord, int x, int y, vec4 cam, usampler2D depth) { float z = float(textureLod(depth, texcoord, 0.0)) / 1000.0f; return vec3((x - cam.x) * z * cam.z, (y - cam.y) * z * cam.w, z); } //Cam is //cx, cy, 1 / fx, 1 / fy vec3 getNormal(vec3 vPosition, vec2 texcoord, int x, int y, vec4 cam, usampler2D depth) { vec3 vPosition_x = getVertex(vec2(texcoord.x + (1.0 / cols), texcoord.y), x + 1, y, cam, depth); vec3 vPosition_y = getVertex(vec2(texcoord.x, texcoord.y + (1.0 / rows)), x, y + 1, cam, depth); vec3 del_x = vPosition_x - vPosition; vec3 del_y = vPosition_y - vPosition; return normalize(cross(del_x, del_y)); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/index_map.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec4 vPosition0; in vec4 vColorTime0; in vec4 vNormRad0; flat in int vertexId; layout(location = 0) out int FragColor; layout(location = 1) out vec4 vPosition1; layout(location = 2) out vec4 vColorTime1; layout(location = 3) out vec4 vNormRad1; void main() { vPosition1 = vPosition0; vColorTime1 = vColorTime0; vNormRad1 = vNormRad0; FragColor = vertexId; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/index_map.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPosition; layout (location = 1) in vec4 vColorTime; layout (location = 2) in vec4 vNormRad; out vec4 vPosition0; out vec4 vColorTime0; out vec4 vNormRad0; flat out int vertexId; uniform mat4 t_inv; uniform vec4 cam; //cx, cy, fx, fy uniform float cols; uniform float rows; uniform float maxDepth; uniform int time; uniform int timeDelta; void main() { vec4 vPosHome = t_inv * vec4(vPosition.xyz, 1.0); float x = 0; float y = 0; if(vPosHome.z > maxDepth || vPosHome.z < 0 || time - vColorTime.w > timeDelta) { x = -10; y = -10; vertexId = 0; } else { x = ((((cam.z * vPosHome.x) / vPosHome.z) + cam.x) - (cols * 0.5)) / (cols * 0.5); y = ((((cam.w * vPosHome.y) / vPosHome.z) + cam.y) - (rows * 0.5)) / (rows * 0.5); vertexId = gl_VertexID; } gl_Position = vec4(x, y, vPosHome.z / maxDepth, 1.0); vPosition0 = vec4(vPosHome.xyz, vPosition.w); vColorTime0 = vColorTime; vNormRad0 = vec4(normalize(mat3(t_inv) * vNormRad.xyz), vNormRad.w); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/init_unstable.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPosition; layout (location = 1) in vec4 vColor; layout (location = 2) in vec4 vNormRad; out vec4 vPosition0; out vec4 vColor0; out vec4 vNormRad0; void main() { vPosition0 = vPosition; vColor0 = vColor; vColor0.y = 0; //Unused vColor0.z = 1; //This sets the vertex's initialisation time vNormRad0 = vNormRad; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/quad.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(triangle_strip, max_vertices = 4) out; out vec2 texcoord; void main() { gl_Position = vec4(1.0, 1.0, 0.0, 1.0); texcoord = vec2(1.0, 1.0); EmitVertex(); gl_Position = vec4(-1.0, 1.0, 0.0, 1.0); texcoord = vec2(0.0, 1.0); EmitVertex(); gl_Position = vec4(1.0,-1.0, 0.0, 1.0); texcoord = vec2(1.0, 0.0); EmitVertex(); gl_Position = vec4(-1.0,-1.0, 0.0, 1.0); texcoord = vec2(0.0, 0.0); EmitVertex(); EndPrimitive(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/resize.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core in vec2 texcoord; out vec4 FragColor; uniform sampler2D eSampler; void main() { FragColor = texture2D(eSampler, texcoord.xy); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/sample.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(points, max_vertices = 1) out; in vec4 vPosition0[]; in vec4 vColorTime0[]; in vec4 vNormRad0[]; flat in int id[]; out vec4 vData; void main() { if(id[0] % 5000 == 0) { vData.xyz = vPosition0[0].xyz; vData.w = vColorTime0[0].z; EmitVertex(); EndPrimitive(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/sample.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPosition; layout (location = 1) in vec4 vColorTime; layout (location = 2) in vec4 vNormRad; out vec4 vPosition0; out vec4 vColorTime0; out vec4 vNormRad0; flat out int id; void main() { vPosition0 = vPosition; vColorTime0 = vColorTime; vNormRad0 = vNormRad; id = gl_VertexID; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/splat.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPosition; layout (location = 1) in vec4 vColor; layout (location = 2) in vec4 vNormRad; uniform mat4 t_inv; uniform vec4 cam; //cx, cy, fx, fy uniform float cols; uniform float rows; uniform float maxDepth; uniform float confThreshold; uniform int time; uniform int maxTime; uniform int timeDelta; out vec4 position; out vec4 normRad; out vec4 colTime; vec3 projectPoint(vec3 p) { return vec3(((((cam.z * p.x) / p.z) + cam.x) - (cols * 0.5)) / (cols * 0.5), ((((cam.w * p.y) / p.z) + cam.y) - (rows * 0.5)) / (rows * 0.5), p.z / maxDepth); } vec3 projectPointImage(vec3 p) { return vec3(((cam.z * p.x) / p.z) + cam.x, ((cam.w * p.y) / p.z) + cam.y, p.z); } void main() { vec4 vPosHome = t_inv * vec4(vPosition.xyz, 1.0); if(vPosHome.z > maxDepth || vPosHome.z < 0 || vPosition.w < confThreshold || time - vColor.w > timeDelta || vColor.w > maxTime) { gl_Position = vec4(1000.0f, 1000.0f, 1000.0f, 1000.0f); gl_PointSize = 0; } else { gl_Position = vec4(projectPoint(vPosHome.xyz), 1.0); colTime = vColor; position = vec4(vPosHome.xyz, vPosition.w); normRad = vec4(normalize(mat3(t_inv) * vNormRad.xyz), vNormRad.w); vec3 x1 = normalize(vec3((normRad.y - normRad.z), -normRad.x, normRad.x)) * normRad.w * 1.41421356; vec3 y1 = cross(normRad.xyz, x1); vec4 proj1 = vec4(projectPointImage(vPosHome.xyz + x1), 1.0); vec4 proj2 = vec4(projectPointImage(vPosHome.xyz + y1), 1.0); vec4 proj3 = vec4(projectPointImage(vPosHome.xyz - y1), 1.0); vec4 proj4 = vec4(projectPointImage(vPosHome.xyz - x1), 1.0); vec2 xs = vec2(min(proj1.x, min(proj2.x, min(proj3.x, proj4.x))), max(proj1.x, max(proj2.x, max(proj3.x, proj4.x)))); vec2 ys = vec2(min(proj1.y, min(proj2.y, min(proj3.y, proj4.y))), max(proj1.y, max(proj2.y, max(proj3.y, proj4.y)))); float xDiff = abs(xs.y - xs.x); float yDiff = abs(ys.y - ys.x); gl_PointSize = max(0, max(xDiff, yDiff)); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/surfels.glsl ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ float getRadius(float depth, float norm_z) { float meanFocal = ((1.0 / abs(cam.z)) + (1.0 / abs(cam.w))) / 2.0; const float sqrt2 = 1.41421356237f; float radius = (depth / meanFocal) * sqrt2; float radius_n = radius; radius_n = radius_n / abs(norm_z); radius_n = min(2.0f * radius, radius_n); return radius_n; } float confidence(float x, float y, float weighting) { const float maxRadDist = 400; //sqrt((width * 0.5)^2 + (height * 0.5)^2) const float twoSigmaSquared = 0.72; //2*(0.6^2) from paper vec2 pixelPosCentered = vec2(x, y) - cam.xy; float radialDist = sqrt(dot(pixelPosCentered, pixelPosCentered)) / maxRadDist; return exp((-(radialDist * radialDist) / twoSigmaSquared)) * weighting; } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/update.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec4 vPosition; layout (location = 1) in vec4 vColor; layout (location = 2) in vec4 vNormRad; out vec4 vPosition0; out vec4 vColor0; out vec4 vNormRad0; uniform float texDim; uniform int time; uniform sampler2D vertSamp; uniform sampler2D colorSamp; uniform sampler2D normSamp; #include "color.glsl" void main() { int intY = gl_VertexID / int(texDim); int intX = gl_VertexID - (intY * int(texDim)); float halfPixel = 0.5 * (1.0f / texDim); float y = (float(intY) / texDim) + halfPixel; float x = (float(intX) / texDim) + halfPixel; vec4 newColor = textureLod(colorSamp, vec2(x, y), 0); //Do averaging here if(newColor.w == -1) { vec4 newPos = textureLod(vertSamp, vec2(x, y), 0); vec4 newNorm = textureLod(normSamp, vec2(x, y), 0); float c_k = vPosition.w; vec3 v_k = vPosition.xyz; float a = newPos.w; vec3 v_g = newPos.xyz; if(newNorm.w < (1.0 + 0.5) * vNormRad.w) { vPosition0 = vec4(((c_k * v_k) + (a * v_g)) / (c_k + a), c_k + a); vec3 oldCol = decodeColor(vColor.x); vec3 newCol = decodeColor(newColor.x); vec3 avgColor = ((c_k * oldCol.xyz) + (a * newCol.xyz)) / (c_k + a); vColor0 = vec4(encodeColor(avgColor), vColor.y, vColor.z, time); vNormRad0 = ((c_k * vNormRad) + (a * newNorm)) / (c_k + a); vNormRad0.xyz = normalize(vNormRad0.xyz); } else { vPosition0 = vPosition; vColor0 = vColor; vNormRad0 = vNormRad; vPosition0.w = c_k + a; vColor0.w = time; } } else { //This point isn't being updated, so just transfer it vPosition0 = vPosition; vColor0 = vColor; vNormRad0 = vNormRad; } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/vertex_feedback.geom ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout(points) in; layout(points, max_vertices = 1) out; in vec4 vPosition[]; in vec4 vColor[]; in vec4 vNormRad[]; in float zVal[]; out vec4 vPosition0; out vec4 vColor0; out vec4 vNormRad0; void main() { if(zVal[0] > 0) { vPosition0 = vPosition[0]; vColor0 = vColor[0]; vNormRad0 = vNormRad[0]; EmitVertex(); EndPrimitive(); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/vertex_feedback.vert ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core layout (location = 0) in vec2 texcoord; out vec4 vPosition; out vec4 vColor; out vec4 vNormRad; out float zVal; uniform sampler2D gSampler; uniform sampler2D cSampler; uniform vec4 cam; //cx, cy, 1/fx, 1/fy uniform float cols; uniform float rows; uniform int time; uniform float maxDepth; #include "surfels.glsl" #include "color.glsl" #include "geometry.glsl" void main() { //Should be guaranteed to be in bounds float x = texcoord.x * cols; float y = texcoord.y * rows; vPosition = vec4(getVertex(texcoord.xy, x, y, cam, gSampler), 1); vColor = textureLod(cSampler, texcoord.xy, 0.0); vec3 vNormLocal = getNormal(vPosition.xyz, texcoord.xy, x, y, cam, gSampler); vNormRad = vec4(vNormLocal, getRadius(vPosition.z, vNormLocal.z)); if(vPosition.z <= 0 || vPosition.z > maxDepth) { zVal = 0; } else { zVal = vPosition.z; } vPosition.w = confidence(x, y, 1.0f); vColor.x = encodeColor(vColor.xyz); vColor.y = 0; //Timestamp vColor.w = float(time); } ================================================ FILE: obj_pose_est/mapping/Core/src/Shaders/visualise_textures.frag ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #version 330 core uniform sampler2D texVerts; uniform float maxDepth; in vec2 texcoord; out vec4 FragColor; void main() { vec4 vertex = texture2D(texVerts, texcoord); if(vertex.z > maxDepth || vertex.z <= 0) { discard; } else { FragColor = 1.0f - vec4(vertex.z / maxDepth); } } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/CholeskyDecomp.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "CholeskyDecomp.h" CholeskyDecomp::CholeskyDecomp() : L(0) { cholmod_start(&Common); } CholeskyDecomp::~CholeskyDecomp() { cholmod_finish(&Common); } void CholeskyDecomp::freeFactor() { assert(L); cholmod_free_factor(&L, &Common); L = 0; } Eigen::VectorXd CholeskyDecomp::solve(const Jacobian & jacobian, const Eigen::VectorXd & residual, const bool firstRun) { cholmod_sparse * At = cholmod_allocate_sparse(jacobian.cols(), jacobian.rows.size(), jacobian.nonZero(), true, true, 0, CHOLMOD_REAL, &Common); int* p = (int*) At->p; int* i = (int*) At->i; double* x = (double*) At->x; int n = 0; *p = n; for(size_t r = 0; r < jacobian.rows.size(); r++) { memcpy(i, jacobian.rows.at(r)->indices, jacobian.rows.at(r)->nonZeros() * sizeof(int)); memcpy(x, jacobian.rows.at(r)->vals, jacobian.rows.at(r)->nonZeros()* sizeof(double)); i += jacobian.rows.at(r)->nonZeros(); x += jacobian.rows.at(r)->nonZeros(); n += jacobian.rows.at(r)->nonZeros(); p++; *p = n; } if(firstRun) { assert(!L); L = cholmod_analyze(At, &Common); } cholmod_factor * L_factor = cholmod_copy_factor(L, &Common); cholmod_factorize(At, L_factor, &Common); cholmod_change_factor(CHOLMOD_REAL, true, false, true, true, L_factor, &Common); cholmod_dense* Arhs = cholmod_zeros(At->ncol, 1, CHOLMOD_REAL, &Common); memcpy(Arhs->x, residual.data(), At->ncol * sizeof(double)); cholmod_dense* Atb = cholmod_zeros(At->nrow, 1, CHOLMOD_REAL, &Common); double alpha[2] = { 1., 0. }; double beta[2] = { 0., 0. }; cholmod_sdmult(At, 0, alpha, beta, Arhs, Atb, &Common); cholmod_dense* Atb_perm = cholmod_solve(CHOLMOD_P, L_factor, Atb, &Common); cholmod_dense * rhs = cholmod_solve(CHOLMOD_L, L_factor, Atb_perm, &Common); cholmod_dense* delta_cm = cholmod_solve(CHOLMOD_Lt, L_factor, rhs, &Common); Eigen::VectorXd delta(rhs->nrow); for(size_t i = 0; i < At->nrow; i++) { delta(((int *)L_factor->Perm)[i]) = ((double*)delta_cm->x)[i]; } cholmod_free_dense(&delta_cm, &Common); cholmod_free_dense(&Atb_perm, &Common); cholmod_free_dense(&Atb, &Common); cholmod_free_dense(&Arhs, &Common); cholmod_free_sparse(&At, &Common); cholmod_free_dense(&rhs, &Common); cholmod_free_factor(&L_factor, &Common); return delta; } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/CholeskyDecomp.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef UTILS_CHOLESKYDECOMP_H_ #define UTILS_CHOLESKYDECOMP_H_ #include #include #include "Jacobian.h" class CholeskyDecomp { public: CholeskyDecomp(); virtual ~CholeskyDecomp(); void freeFactor(); Eigen::VectorXd solve(const Jacobian & jacobian, const Eigen::VectorXd & residual, const bool firstRun); private: cholmod_common Common; cholmod_factor * L; }; #endif /* UTILS_CHOLESKYDECOMP_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/DeformationGraph.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "CholeskyDecomp.h" #include "DeformationGraph.h" DeformationGraph::DeformationGraph(int k, std::vector * sourceVertices) : k(k), initialised(false), wRot(1), wReg(10), wCon(100), sourceVertices(sourceVertices), graphCloud(new std::vector), lastPointCount(0), cholesky(new CholeskyDecomp) {} DeformationGraph::~DeformationGraph() { if(initialised) { graphNodes.clear(); } delete graphCloud; delete cholesky; } std::vector & DeformationGraph::getGraph() { return graph; } std::vector & DeformationGraph::getGraphTimes() { return sampledGraphTimes; } void DeformationGraph::initialiseGraph(std::vector * customGraph, std::vector * graphTimeMap) { graphCloud->clear(); sampledGraphTimes.clear(); sampledGraphTimes.insert(sampledGraphTimes.end(), graphTimeMap->begin(), graphTimeMap->end()); graphCloud->insert(graphCloud->end(), customGraph->begin(), customGraph->end()); graphNodes.clear(); graph.clear(); graphNodes.resize(graphCloud->size()); for(unsigned int i = 0; i < graphCloud->size(); i++) { graphNodes[i].id = i; graphNodes[i].enabled = true; graphNodes[i].position = graphCloud->at(i); graphNodes[i].translation = Eigen::Vector3f::Zero(); graphNodes[i].rotation.setIdentity(); graph.push_back(&graphNodes[i]); } connectGraphSeq(); initialised = true; } void DeformationGraph::appendVertices(std::vector * vertexTimeMap, unsigned int originalPointEnd) { vertexMap.resize(lastPointCount); weightVerticesSeq(vertexTimeMap); lastPointCount = originalPointEnd; } void DeformationGraph::applyGraphToPoses(std::vector & poses) { assert(poses.size() == poseMap.size() && initialised); Eigen::Vector3f newPosition; Eigen::Matrix3f rotation; for(size_t i = 0; i < poses.size(); i++) { std::vector & weightMap = poseMap.at(i); newPosition = Eigen::Vector3f::Zero(); rotation = Eigen::Matrix3f::Zero(); for(size_t j = 0; j < weightMap.size(); j++) { newPosition += weightMap.at(j).weight * (graph.at(weightMap.at(j).node)->rotation * (poses.at(i)->topRightCorner(3, 1) - graph.at(weightMap.at(j).node)->position) + graph.at(weightMap.at(j).node)->position + graph.at(weightMap.at(j).node)->translation); rotation += weightMap.at(j).weight * graph.at(weightMap.at(j).node)->rotation; } Eigen::Matrix3f newRotation = rotation * poses.at(i)->topLeftCorner(3, 3); Eigen::JacobiSVD svd(newRotation, Eigen::ComputeFullU | Eigen::ComputeFullV); poses.at(i)->topRightCorner(3, 1) = newPosition; poses.at(i)->topLeftCorner(3, 3) = svd.matrixU() * svd.matrixV().transpose(); } } void DeformationGraph::setPosesSeq(std::vector * poseTimeMap, const std::vector & poses) { poseMap.clear(); const unsigned int lookBack = 20; std::vector pointIdxNKNSearch(k + 1); std::vector pointNKNSquaredDistance(k + 1); for(unsigned int i = 0; i < poses.size(); i++) { unsigned long long int poseTime = poseTimeMap->at(i); unsigned int foundIndex = 0; int imin = 0; int imax = sampledGraphTimes.size() - 1; int imid = (imin + imax) / 2; while(imax >= imin) { imid = (imin + imax) / 2; if (sampledGraphTimes[imid] < poseTime) { imin = imid + 1; } else if(sampledGraphTimes[imid] > poseTime) { imax = imid - 1; } else { break; } } imin = std::min(imin, (int)sampledGraphTimes.size() - 1); if(abs(int64_t(sampledGraphTimes[imin]) - int64_t(poseTime)) <= abs(int64_t(sampledGraphTimes[imid]) - int64_t(poseTime)) && abs(int64_t(sampledGraphTimes[imin]) - int64_t(poseTime)) <= abs(int64_t(sampledGraphTimes[imax]) - int64_t(poseTime))) { foundIndex = imin; } else if(abs(int64_t(sampledGraphTimes[imid]) - int64_t(poseTime)) <= abs(int64_t(sampledGraphTimes[imin]) - int64_t(poseTime)) && abs(int64_t(sampledGraphTimes[imid]) - int64_t(poseTime)) <= abs(int64_t(sampledGraphTimes[imax]) - int64_t(poseTime))) { foundIndex = imid; } else { foundIndex = imax; } std::vector > nearNodes; if(foundIndex == graphCloud->size()) { foundIndex = graphCloud->size() - 1; } unsigned int distanceBack = 0; for(int j = (int)foundIndex; j >= 0; j--) { std::pair newNode; newNode.first = (graphCloud->at(j) - poses.at(i).topRightCorner(3, 1)).norm(); newNode.second = j; nearNodes.push_back(newNode); if(++distanceBack == lookBack) { break; } } if(distanceBack != lookBack) { for(unsigned int j = foundIndex + 1; j < sampledGraphTimes.size(); j++) { std::pair newNode; newNode.first = (graphCloud->at(j) - poses.at(i).topRightCorner(3, 1)).norm(); newNode.second = j; nearNodes.push_back(newNode); if(++distanceBack == lookBack) { break; } } } std::sort(nearNodes.begin(), nearNodes.end(), [](const std::pair &left, const std::pair &right) {return left.first < right.first;}); Eigen::Vector3f vertexPosition = poses.at(i).topRightCorner(3, 1); double dMax = nearNodes.at(k).first; std::vector newMap; double weightSum = 0; for(unsigned int j = 0; j < (unsigned int)k; j++) { newMap.push_back(VertexWeightMap(pow(1.0f - (vertexPosition - graphNodes[nearNodes.at(j).second].position).norm() / dMax, 2), nearNodes.at(j).second)); weightSum += newMap.back().weight; } for(unsigned int j = 0; j < newMap.size(); j++) { newMap.at(j).weight /= weightSum; } VertexWeightMap::sort(newMap, graph); poseMap.push_back(newMap); } } void DeformationGraph::connectGraphSeq() { for(int i = 0; i < k / 2; i++) { for(int n = 0; n < k + 1; n++) { if(i == n) { continue; } graphNodes[i].neighbours.push_back(n); } } for(unsigned int i = k / 2; i < graphCloud->size() - (k / 2); i++) { for(int n = 0; n < k / 2; n++) { graphNodes[i].neighbours.push_back(i - (n + 1)); graphNodes[i].neighbours.push_back(i + (n + 1)); } } for(unsigned int i = graphCloud->size() - (k / 2); i < graphCloud->size(); i++) { for(unsigned int n = graphCloud->size() - (k + 1); n < graphCloud->size(); n++) { if(i == n) { continue; } graphNodes[i].neighbours.push_back(n); } } } void DeformationGraph::weightVerticesSeq(std::vector * vertexTimeMap) { const unsigned int lookBack = 20; std::vector pointIdxNKNSearch(k + 1); std::vector pointNKNSquaredDistance(k + 1); for(unsigned int i = lastPointCount; i < sourceVertices->size(); i++) { unsigned long long int vertexTime = vertexTimeMap->at(i); unsigned int foundIndex = 0; int imin = 0; int imax = sampledGraphTimes.size() - 1; int imid = (imin + imax) / 2; while(imax >= imin) { imid = (imin + imax) / 2; if (sampledGraphTimes[imid] < vertexTime) { imin = imid + 1; } else if(sampledGraphTimes[imid] > vertexTime) { imax = imid - 1; } else { break; } } imin = std::min(imin, (int)sampledGraphTimes.size() - 1); if(abs(int64_t(sampledGraphTimes[imin]) - int64_t(vertexTime)) <= abs(int64_t(sampledGraphTimes[imid]) - int64_t(vertexTime)) && abs(int64_t(sampledGraphTimes[imin]) - int64_t(vertexTime)) <= abs(int64_t(sampledGraphTimes[imax]) - int64_t(vertexTime))) { foundIndex = imin; } else if(abs(int64_t(sampledGraphTimes[imid]) - int64_t(vertexTime)) <= abs(int64_t(sampledGraphTimes[imin]) - int64_t(vertexTime)) && abs(int64_t(sampledGraphTimes[imid]) - int64_t(vertexTime)) <= abs(int64_t(sampledGraphTimes[imax]) - int64_t(vertexTime))) { foundIndex = imid; } else { foundIndex = imax; } std::vector > nearNodes; if(foundIndex == graphCloud->size()) { foundIndex = graphCloud->size() - 1; } unsigned int distanceBack = 0; for(int j = (int)foundIndex; j >= 0; j--) { std::pair newNode; newNode.first = (graphCloud->at(j) - sourceVertices->at(i)).norm(); newNode.second = j; nearNodes.push_back(newNode); if(++distanceBack == lookBack) { break; } } if(distanceBack != lookBack) { for(unsigned int j = foundIndex + 1; j < sampledGraphTimes.size(); j++) { std::pair newNode; newNode.first = (graphCloud->at(j) - sourceVertices->at(i)).norm(); newNode.second = j; nearNodes.push_back(newNode); if(++distanceBack == lookBack) { break; } } } std::sort(nearNodes.begin(), nearNodes.end(), [](const std::pair &left, const std::pair &right) {return left.first < right.first;}); Eigen::Vector3f vertexPosition = sourceVertices->at(i); double dMax = nearNodes.at(k).first; std::vector newMap; double weightSum = 0; for(unsigned int j = 0; j < (unsigned int)k; j++) { newMap.push_back(VertexWeightMap(pow(1.0f - (vertexPosition - graphNodes[nearNodes.at(j).second].position).norm() / dMax, 2), nearNodes.at(j).second)); weightSum += newMap.back().weight; } for(unsigned int j = 0; j < newMap.size(); j++) { newMap.at(j).weight /= weightSum; } VertexWeightMap::sort(newMap, graph); vertexMap.push_back(newMap); } } void DeformationGraph::applyGraphToVertices() { Eigen::Vector3f position; for(unsigned int i = 0; i < sourceVertices->size(); i++) { computeVertexPosition(i, position); sourceVertices->at(i) = position; } } void DeformationGraph::addConstraint(int vertexId, Eigen::Vector3f & target) { assert(initialised); //Overwrites old constraint for(unsigned int i = 0; i < constraints.size(); i++) { if(constraints.at(i).vertexId == vertexId) { constraints.at(i) = Constraint(vertexId, target); return; } } constraints.push_back(Constraint(vertexId, target)); } void DeformationGraph::addRelativeConstraint(int vertexId, int targetId) { assert(initialised); //Overwrites old constraint for(unsigned int i = 0; i < constraints.size(); i++) { if(constraints.at(i).vertexId == vertexId) { constraints.at(i) = Constraint(vertexId, targetId); return; } } constraints.push_back(Constraint(vertexId, targetId)); } void DeformationGraph::clearConstraints() { constraints.clear(); } bool DeformationGraph::optimiseGraphSparse(float & error, float & meanConsErr, const bool fernMatch, const unsigned long long int lastDeformTime) { assert(initialised); TICK("opt"); meanConsErr = nonRelativeConstraintError(); if(fernMatch && meanConsErr < 0.06) { TOCK("opt"); return false; } int maxRows = (eRotRows + eRegRows * k) * graph.size() + eConRows * constraints.size(); int numCols = 0; int backSet = graph.size() * numVariables; for(size_t i = 0; i < graph.size(); i++) { graph.at(i)->enabled = sampledGraphTimes.at(i) > lastDeformTime; if(graph.at(i)->enabled) { numCols += numVariables; backSet -= numVariables; } } Eigen::VectorXd residual = sparseResidual(maxRows); Jacobian jacobian; sparseJacobian(jacobian, residual.rows(), numCols, backSet); error = residual.squaredNorm(); double lastError = error; double errorDiff = 0; // std::cout << "Initial error: " << error << ", " << meanConsErr << std::endl; int iter = 0; while(iter++ < 3) { Eigen::VectorXd delta = cholesky->solve(jacobian, -residual, iter == 1); applyDeltaSparse(delta); residual = sparseResidual(maxRows); error = residual.squaredNorm(); errorDiff = error - lastError; // std::cout << "Iteration " << iter << ": " << error << std::endl; if(error > lastError || delta.norm() < 1e-2 || error < 1e-3 || fabs(errorDiff) < 1e-5 * error || (iter == 1 && fernMatch && error > 10.0f)) { break; } lastError = error; sparseJacobian(jacobian, residual.rows(), numCols, backSet); } cholesky->freeFactor(); TOCK("opt"); meanConsErr = nonRelativeConstraintError(); // std::cout << "Final error: " << error << ", " << meanConsErr << std::endl; return true; } void DeformationGraph::sparseJacobian(Jacobian & jacobian, const int numRows, const int numCols, const int backSet) { std::vector rows(numRows); //We know exact counts per row... int lastRow = 0; for(unsigned int j = 0; j < graph.size(); j++) { if(graph.at(j)->enabled) { int colOffset = graph.at(j)->id * numVariables; //No weights for rotation as rotation weight = 1 const Eigen::Matrix3f & rotation = graph.at(j)->rotation; rows[lastRow] = new OrderedJacobianRow(6); rows[lastRow + 1] = new OrderedJacobianRow(6); rows[lastRow + 2] = new OrderedJacobianRow(6); rows[lastRow + 3] = new OrderedJacobianRow(3); rows[lastRow + 4] = new OrderedJacobianRow(3); rows[lastRow + 5] = new OrderedJacobianRow(3); rows[lastRow]->append(colOffset - backSet, rotation(0, 1)); rows[lastRow]->append(colOffset + 1 - backSet, rotation(1, 1)); rows[lastRow]->append(colOffset + 2 - backSet, rotation(2, 1)); rows[lastRow]->append(colOffset + 3 - backSet, rotation(0, 0)); rows[lastRow]->append(colOffset + 4 - backSet, rotation(1, 0)); rows[lastRow]->append(colOffset + 5 - backSet, rotation(2, 0)); rows[lastRow + 1]->append(colOffset - backSet, rotation(0, 2)); rows[lastRow + 1]->append(colOffset + 1 - backSet, rotation(1, 2)); rows[lastRow + 1]->append(colOffset + 2 - backSet, rotation(2, 2)); rows[lastRow + 1]->append(colOffset + 6 - backSet, rotation(0, 0)); rows[lastRow + 1]->append(colOffset + 7 - backSet, rotation(1, 0)); rows[lastRow + 1]->append(colOffset + 8 - backSet, rotation(2, 0)); rows[lastRow + 2]->append(colOffset + 3 - backSet, rotation(0, 2)); rows[lastRow + 2]->append(colOffset + 4 - backSet, rotation(1, 2)); rows[lastRow + 2]->append(colOffset + 5 - backSet, rotation(2, 2)); rows[lastRow + 2]->append(colOffset + 6 - backSet, rotation(0, 1)); rows[lastRow + 2]->append(colOffset + 7 - backSet, rotation(1, 1)); rows[lastRow + 2]->append(colOffset + 8 - backSet, rotation(2, 1)); rows[lastRow + 3]->append(colOffset - backSet, 2*rotation(0, 0)); rows[lastRow + 3]->append(colOffset + 1 - backSet, 2*rotation(1, 0)); rows[lastRow + 3]->append(colOffset + 2 - backSet, 2*rotation(2, 0)); rows[lastRow + 4]->append(colOffset + 3 - backSet, 2*rotation(0, 1)); rows[lastRow + 4]->append(colOffset + 4 - backSet, 2*rotation(1, 1)); rows[lastRow + 4]->append(colOffset + 5 - backSet, 2*rotation(2, 1)); rows[lastRow + 5]->append(colOffset + 6 - backSet, 2*rotation(0, 2)); rows[lastRow + 5]->append(colOffset + 7 - backSet, 2*rotation(1, 2)); rows[lastRow + 5]->append(colOffset + 8 - backSet, 2*rotation(2, 2)); lastRow += eRotRows; } } for(unsigned int j = 0; j < graph.size(); j++) { int colOffset = graph.at(j)->id * numVariables; //For each neighbour for(unsigned int n = 0; n < graph.at(j)->neighbours.size(); n++) { if(graph.at(graph.at(j)->neighbours.at(n))->enabled || graph.at(j)->enabled) { rows[lastRow] = new OrderedJacobianRow(5); rows[lastRow + 1] = new OrderedJacobianRow(5); rows[lastRow + 2] = new OrderedJacobianRow(5); Eigen::Vector3f delta = graph.at(graph.at(j)->neighbours.at(n))->position - graph.at(j)->position; int colOffsetN = graph.at(graph.at(j)->neighbours.at(n))->id * numVariables; assert(colOffset != colOffsetN); if(colOffsetN < colOffset && graph.at(graph.at(j)->neighbours.at(n))->enabled) { rows[lastRow]->append(colOffsetN + 9 - backSet, -1.0 * sqrt(wReg)); rows[lastRow + 1]->append(colOffsetN + 10 - backSet, -1.0 * sqrt(wReg)); rows[lastRow + 2]->append(colOffsetN + 11 - backSet, -1.0 * sqrt(wReg)); } if(graph.at(j)->enabled) { rows[lastRow]->append(colOffset - backSet, delta(0) * sqrt(wReg)); rows[lastRow]->append(colOffset + 3 - backSet, delta(1) * sqrt(wReg)); rows[lastRow]->append(colOffset + 6 - backSet, delta(2) * sqrt(wReg)); rows[lastRow]->append(colOffset + 9 - backSet, 1.0 * sqrt(wReg)); rows[lastRow + 1]->append(colOffset + 1 - backSet, delta(0) * sqrt(wReg)); rows[lastRow + 1]->append(colOffset + 4 - backSet, delta(1) * sqrt(wReg)); rows[lastRow + 1]->append(colOffset + 7 - backSet, delta(2) * sqrt(wReg)); rows[lastRow + 1]->append(colOffset + 10 - backSet, 1.0 * sqrt(wReg)); rows[lastRow + 2]->append(colOffset + 2 - backSet, delta(0) * sqrt(wReg)); rows[lastRow + 2]->append(colOffset + 5 - backSet, delta(1) * sqrt(wReg)); rows[lastRow + 2]->append(colOffset + 8 - backSet, delta(2) * sqrt(wReg)); rows[lastRow + 2]->append(colOffset + 11 - backSet, 1.0 * sqrt(wReg)); } if(colOffsetN > colOffset && graph.at(graph.at(j)->neighbours.at(n))->enabled) { rows[lastRow]->append(colOffsetN + 9 - backSet, -1.0 * sqrt(wReg)); rows[lastRow + 1]->append(colOffsetN + 10 - backSet, -1.0 * sqrt(wReg)); rows[lastRow + 2]->append(colOffsetN + 11 - backSet, -1.0 * sqrt(wReg)); } lastRow += eRegRows; } } } for(unsigned int l = 0; l < constraints.size(); l++) { const std::vector & weightMap = vertexMap.at(constraints.at(l).vertexId); bool nodeInfluences = false; for(size_t i = 0; i < weightMap.size(); i++) { if(graph.at(weightMap.at(i).node)->enabled) { nodeInfluences = true; break; } } if(constraints.at(l).relative && !nodeInfluences) { const std::vector & relWeightMap = vertexMap.at(constraints.at(l).targetId); for(size_t i = 0; i < relWeightMap.size(); i++) { if(graph.at(relWeightMap.at(i).node)->enabled) { nodeInfluences = true; break; } } } if(nodeInfluences) { Eigen::Vector3f sourcePosition = sourceVertices->at(constraints.at(l).vertexId); rows[lastRow] = new OrderedJacobianRow(4 * k * 2); rows[lastRow + 1] = new OrderedJacobianRow(4 * k * 2); rows[lastRow + 2] = new OrderedJacobianRow(4 * k * 2); assert(graph.at(weightMap.at(0).node)->id < graph.at(weightMap.at(1).node)->id); if(constraints.at(l).relative) { Eigen::Vector3f targetPosition = sourceVertices->at(constraints.at(l).targetId); std::vector & relWeightMap = vertexMap.at(constraints.at(l).targetId); for(unsigned int i = 0; i < relWeightMap.size(); i++) { relWeightMap.at(i).relative = true; } std::vector weightMapMixed; weightMapMixed.insert(weightMapMixed.end(), weightMap.begin(), weightMap.end()); weightMapMixed.insert(weightMapMixed.end(), relWeightMap.begin(), relWeightMap.end()); VertexWeightMap::sort(weightMapMixed, graph); std::map checkList; for(unsigned int i = 0; i < weightMapMixed.size(); i++) { if(graph.at(weightMapMixed.at(i).node)->enabled) { int colOffset = graph.at(weightMapMixed.at(i).node)->id * numVariables; if(weightMapMixed.at(i).relative) { Eigen::Vector3f delta = (graph.at(weightMapMixed.at(i).node)->position - targetPosition) * weightMapMixed.at(i).weight; //We have to sum the Jacobian entries in this case if(checkList[graph.at(weightMapMixed.at(i).node)->id]) { rows[lastRow]->addTo(colOffset - backSet, delta(0), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 3 - backSet, delta(1), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 6 - backSet, delta(2), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 9 - backSet, -weightMapMixed.at(i).weight, sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 1 - backSet, delta(0), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 4 - backSet, delta(1), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 7 - backSet, delta(2), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 10 - backSet, -weightMapMixed.at(i).weight, sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 2 - backSet, delta(0), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 5 - backSet, delta(1), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 8 - backSet, delta(2), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 11 - backSet, -weightMapMixed.at(i).weight, sqrt(wCon)); } else { rows[lastRow]->append(colOffset - backSet, delta(0) * sqrt(wCon)); rows[lastRow]->append(colOffset + 3 - backSet, delta(1) * sqrt(wCon)); rows[lastRow]->append(colOffset + 6 - backSet, delta(2) * sqrt(wCon)); rows[lastRow]->append(colOffset + 9 - backSet, -weightMapMixed.at(i).weight * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 1 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 4 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 7 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 10 - backSet, -weightMapMixed.at(i).weight * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 2 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 5 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 8 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 11 - backSet, -weightMapMixed.at(i).weight * sqrt(wCon)); } } else { Eigen::Vector3f delta = (sourcePosition - graph.at(weightMapMixed.at(i).node)->position) * weightMapMixed.at(i).weight; //We have to sum the Jacobian entries in this case if(checkList[graph.at(weightMapMixed.at(i).node)->id]) { rows[lastRow]->addTo(colOffset - backSet, delta(0), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 3 - backSet, delta(1), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 6 - backSet, delta(2), sqrt(wCon)); rows[lastRow]->addTo(colOffset + 9 - backSet, weightMapMixed.at(i).weight, sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 1 - backSet, delta(0), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 4 - backSet, delta(1), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 7 - backSet, delta(2), sqrt(wCon)); rows[lastRow + 1]->addTo(colOffset + 10 - backSet, weightMapMixed.at(i).weight, sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 2 - backSet, delta(0), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 5 - backSet, delta(1), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 8 - backSet, delta(2), sqrt(wCon)); rows[lastRow + 2]->addTo(colOffset + 11 - backSet, weightMapMixed.at(i).weight, sqrt(wCon)); } else { rows[lastRow]->append(colOffset - backSet, delta(0) * sqrt(wCon)); rows[lastRow]->append(colOffset + 3 - backSet, delta(1) * sqrt(wCon)); rows[lastRow]->append(colOffset + 6 - backSet, delta(2) * sqrt(wCon)); rows[lastRow]->append(colOffset + 9 - backSet, weightMapMixed.at(i).weight * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 1 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 4 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 7 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 10 - backSet, weightMapMixed.at(i).weight * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 2 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 5 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 8 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 11 - backSet, weightMapMixed.at(i).weight * sqrt(wCon)); } } checkList[graph.at(weightMapMixed.at(i).node)->id] = true; } } } else { //Populate each column on the current Jacobian block rows //WARNING: Assumes weightMap is sorted by id! for(unsigned int i = 0; i < weightMap.size(); i++) { if(graph.at(weightMap.at(i).node)->enabled) { int colOffset = graph.at(weightMap.at(i).node)->id * numVariables; Eigen::Vector3f delta = (sourcePosition - graph.at(weightMap.at(i).node)->position) * weightMap.at(i).weight; rows[lastRow]->append(colOffset - backSet, delta(0) * sqrt(wCon)); rows[lastRow]->append(colOffset + 3 - backSet, delta(1) * sqrt(wCon)); rows[lastRow]->append(colOffset + 6 - backSet, delta(2) * sqrt(wCon)); rows[lastRow]->append(colOffset + 9 - backSet, weightMap.at(i).weight * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 1 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 4 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 7 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 1]->append(colOffset + 10 - backSet, weightMap.at(i).weight * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 2 - backSet, delta(0) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 5 - backSet, delta(1) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 8 - backSet, delta(2) * sqrt(wCon)); rows[lastRow + 2]->append(colOffset + 11 - backSet, weightMap.at(i).weight * sqrt(wCon)); } } } lastRow += eConRows; } } assert(lastRow == numRows); jacobian.assign(rows, numCols); } Eigen::VectorXd DeformationGraph::sparseResidual(const int maxRows) { //Now the residual Eigen::VectorXd residual(maxRows); int numRows = 0; for(unsigned int j = 0; j < graph.size(); j++) { if(graph.at(j)->enabled) { //No weights for rotation as rotation weight = 1 const Eigen::Matrix3f & rotation = graph.at(j)->rotation; //ab + de + gh residual(numRows) = rotation.col(0).dot(rotation.col(1)); //ac + df + gi residual(numRows + 1) = rotation.col(0).dot(rotation.col(2)); //bc + ef + hi residual(numRows + 2) = rotation.col(1).dot(rotation.col(2)); //a^2 + d^2 + g^2 - 1 residual(numRows + 3) = (rotation.col(0).dot(rotation.col(0)) - 1.0); //b^2 + e^2 + h^2 - 1 residual(numRows + 4) = (rotation.col(1).dot(rotation.col(1)) - 1.0); //c^2 + f^2 + i^2 - 1 residual(numRows + 5) = (rotation.col(2).dot(rotation.col(2)) - 1.0); numRows += eRotRows; } } for(unsigned int j = 0; j < graph.size(); j++) { for(unsigned int n = 0; n < graph.at(j)->neighbours.size(); n++) { if(graph.at(graph.at(j)->neighbours.at(n))->enabled || graph.at(j)->enabled) { residual.segment(numRows, 3) = (graph.at(j)->rotation * (graph.at(graph.at(j)->neighbours.at(n))->position - graph.at(j)->position) + graph.at(j)->position + graph.at(j)->translation - (graph.at(graph.at(j)->neighbours.at(n))->position + graph.at(graph.at(j)->neighbours.at(n))->translation)).cast() * sqrt(wReg); numRows += eRegRows; } } } for(unsigned int l = 0; l < constraints.size(); l++) { const std::vector & weightMap = vertexMap.at(constraints.at(l).vertexId); bool nodeInfluences = false; for(size_t i = 0; i < weightMap.size(); i++) { if(graph.at(weightMap.at(i).node)->enabled) { nodeInfluences = true; break; } } if(constraints.at(l).relative && !nodeInfluences) { const std::vector & relWeightMap = vertexMap.at(constraints.at(l).targetId); for(size_t i = 0; i < relWeightMap.size(); i++) { if(graph.at(relWeightMap.at(i).node)->enabled) { nodeInfluences = true; break; } } } if(nodeInfluences) { if(constraints.at(l).relative) { Eigen::Vector3f srcPos, tarPos; computeVertexPosition(constraints.at(l).vertexId, srcPos); computeVertexPosition(constraints.at(l).targetId, tarPos); residual.segment(numRows, 3) = (srcPos - tarPos).cast() * sqrt(wCon); } else { Eigen::Vector3f position; computeVertexPosition(constraints.at(l).vertexId, position); residual.segment(numRows, 3) = (position - constraints.at(l).targetPosition).cast() * sqrt(wCon); } numRows += eConRows; } } residual.conservativeResize(numRows); return residual; } void DeformationGraph::resetGraph() { for(unsigned int j = 0; j < graph.size(); j++) { graph.at(j)->rotation.setIdentity(); graph.at(j)->translation.setIdentity(); } } void DeformationGraph::applyDeltaSparse(Eigen::VectorXd & delta) { assert(initialised); //Current row int z = 0; for(unsigned int j = 0; j < graph.size(); j++) { if(graph.at(j)->enabled) { const_cast(graph.at(j)->rotation.data())[0] += delta(z + 0); const_cast(graph.at(j)->rotation.data())[1] += delta(z + 1); const_cast(graph.at(j)->rotation.data())[2] += delta(z + 2); const_cast(graph.at(j)->rotation.data())[3] += delta(z + 3); const_cast(graph.at(j)->rotation.data())[4] += delta(z + 4); const_cast(graph.at(j)->rotation.data())[5] += delta(z + 5); const_cast(graph.at(j)->rotation.data())[6] += delta(z + 6); const_cast(graph.at(j)->rotation.data())[7] += delta(z + 7); const_cast(graph.at(j)->rotation.data())[8] += delta(z + 8); const_cast(graph.at(j)->translation.data())[0] += delta(z + 9); const_cast(graph.at(j)->translation.data())[1] += delta(z + 10); const_cast(graph.at(j)->translation.data())[2] += delta(z + 11); z += numVariables; } } } void DeformationGraph::computeVertexPosition(int vertexId, Eigen::Vector3f & position) { assert(initialised); std::vector & weightMap = vertexMap.at(vertexId); position(0) = 0; position(1) = 0; position(2) = 0; Eigen::Vector3f sourcePosition = sourceVertices->at(vertexId); for(unsigned int i = 0; i < weightMap.size(); i++) { position += weightMap.at(i).weight * (graph.at(weightMap.at(i).node)->rotation * (sourcePosition - graph.at(weightMap.at(i).node)->position) + graph.at(weightMap.at(i).node)->position + graph.at(weightMap.at(i).node)->translation); } } float DeformationGraph::nonRelativeConstraintError() { float result = 0; for(unsigned int l = 0; l < constraints.size(); l++) { if(!constraints.at(l).relative) { Eigen::Vector3f position; computeVertexPosition(constraints.at(l).vertexId, position); result += (position - constraints.at(l).targetPosition).norm(); } } return result / constraints.size(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/DeformationGraph.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef DEFORMATIONGRAPH_H_ #define DEFORMATIONGRAPH_H_ #include #include "Stopwatch.h" #include "GraphNode.h" #include "Jacobian.h" /** * This is basically and object-oriented type approach. Using an array based approach would be faster... */ class CholeskyDecomp; class DeformationGraph { public: DeformationGraph(int k, std::vector * sourceVertices); virtual ~DeformationGraph(); void initialiseGraph(std::vector * customGraph, std::vector * graphTimeMap); void appendVertices(std::vector * vertexTimeMap, unsigned int originalPointEnd); //This clears the pose map... void setPosesSeq(std::vector * poseTimeMap, const std::vector & poses); //Stores a weight and node pointer for a vertex class VertexWeightMap { public: VertexWeightMap(double weight, int node) : weight(weight), node(node), relative(false) {} double weight; int node; bool relative; /** * BubblesortLOL * @param list * @param graph */ static void sort(std::vector & list, std::vector & graph) { bool done = false; int size = list.size(); while(!done) { done = true; for(int i = 0; i < size - 1; i++) { if(graph.at(list[i].node)->id > graph.at(list[i + 1].node)->id) { done = false; std::swap(list[i], list[i + 1]); } } size--; } } }; std::vector & getGraph(); std::vector & getGraphTimes(); void addConstraint(int vertexId, Eigen::Vector3f & target); void addRelativeConstraint(int vertexId, int targetId); void clearConstraints(); void applyGraphToVertices(); void applyGraphToPoses(std::vector & poses); bool optimiseGraphSparse(float & error, float & meanConsErr, const bool fernMatch, const unsigned long long int lastDeformTime); void resetGraph(); bool isInit() { return initialised; } //Number of neighbours const int k; private: bool initialised; //From paper const double wRot; const double wReg; const double wCon; static const int numVariables = 12; static const int eRotRows = 6; static const int eRegRows = 3; static const int eConRows = 3; //Graph itself std::vector graphNodes; std::vector graph; //Maps vertex indices to neighbours and weights std::vector > vertexMap; std::vector * sourceVertices; //Maps pose indices to neighbours and weights std::vector > poseMap; //Stores a vertex constraint class Constraint { public: Constraint(int vertexId, Eigen::Vector3f & targetPosition) : vertexId(vertexId), targetPosition(targetPosition), relative(false), targetId(-1) {} Constraint(int vertexId, int targetId) : vertexId(vertexId), targetPosition(Eigen::Vector3f::Zero()), relative(true), targetId(targetId) {} int vertexId; Eigen::Vector3f targetPosition; bool relative; int targetId; }; std::vector constraints; std::vector * graphCloud; std::vector sampledGraphTimes; unsigned int lastPointCount; void connectGraphSeq(); void weightVerticesSeq(std::vector * vertexTimeMap); void computeVertexPosition(int vertexId, Eigen::Vector3f & position); void sparseJacobian(Jacobian & jacobian, const int numRows, const int numCols, const int backSet); Eigen::VectorXd sparseResidual(const int maxRows); void applyDeltaSparse(Eigen::VectorXd & delta); CholeskyDecomp * cholesky; float nonRelativeConstraintError(); }; #endif /* DEFORMATIONGRAPH_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/GPUConfig.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * * This file contains a mapping between GPU identifier strings given by CUDA * and optimal thread/block pairs for the tracking reductions. If your GPU * isn't here, run the GPUTest program I've included in the code base. */ #ifndef GPUCONFIG_H_ #define GPUCONFIG_H_ #include #include #include #include "../Cuda/convenience.cuh" class GPUConfig { public: static GPUConfig & getInstance() { static GPUConfig instance; return instance; } int icpStepThreads; int icpStepBlocks; int rgbStepThreads; int rgbStepBlocks; int rgbResThreads; int rgbResBlocks; int so3StepThreads; int so3StepBlocks; private: GPUConfig() : icpStepThreads(128), icpStepBlocks(112), rgbStepThreads(128), rgbStepBlocks(112), rgbResThreads(256), rgbResBlocks(336), so3StepThreads(160), so3StepBlocks(64) { cudaDeviceProp prop; cudaSafeCall(cudaGetDeviceProperties(&prop, 0)); std::string dev(prop.name); icpStepMap["GeForce GTX 780 Ti"] = std::pair(128, 112); rgbStepMap["GeForce GTX 780 Ti"] = std::pair(128, 112); rgbResMap["GeForce GTX 780 Ti"] = std::pair(256, 336); so3StepMap["GeForce GTX 780 Ti"] = std::pair(160, 64); icpStepMap["GeForce GTX 880M"] = std::pair(512, 16); rgbStepMap["GeForce GTX 880M"] = std::pair(512, 16); rgbResMap["GeForce GTX 880M"] = std::pair(256, 64); so3StepMap["GeForce GTX 880M"] = std::pair(384, 16); icpStepMap["GeForce GTX 980"] = std::pair(512, 32); rgbStepMap["GeForce GTX 980"] = std::pair(160, 64); rgbResMap["GeForce GTX 980"] = std::pair(128, 512); so3StepMap["GeForce GTX 980"] = std::pair(240, 48); icpStepMap["GeForce GTX 970"] = std::pair(128, 48); rgbStepMap["GeForce GTX 970"] = std::pair(160, 64); rgbResMap["GeForce GTX 970"] = std::pair(128, 272); so3StepMap["GeForce GTX 970"] = std::pair(96, 64); icpStepMap["GeForce GTX 965M"] = std::pair(256, 32); rgbStepMap["GeForce GTX 965M"] = std::pair(224, 16); rgbResMap["GeForce GTX 965M"] = std::pair(384, 480); so3StepMap["GeForce GTX 965M"] = std::pair(160, 32); icpStepMap["GeForce GTX 675MX"] = std::pair(128, 80); rgbStepMap["GeForce GTX 675MX"] = std::pair(128, 48); rgbResMap["GeForce GTX 675MX"] = std::pair(128, 80); so3StepMap["GeForce GTX 675MX"] = std::pair(128, 32); icpStepMap["Quadro K620M"] = std::pair(32, 48); rgbStepMap["Quadro K620M"] = std::pair(128, 16); rgbResMap["Quadro K620M"] = std::pair(448, 48); so3StepMap["Quadro K620M"] = std::pair(32, 48); icpStepMap["GeForce GTX TITAN"] = std::pair(128, 96); rgbStepMap["GeForce GTX TITAN"] = std::pair(112, 96); rgbResMap["GeForce GTX TITAN"] = std::pair(256, 416); so3StepMap["GeForce GTX TITAN"] = std::pair(128, 64); icpStepMap["GeForce GTX TITAN X"] = std::pair(256, 96); rgbStepMap["GeForce GTX TITAN X"] = std::pair(256, 64); rgbResMap["GeForce GTX TITAN X"] = std::pair(96, 496); so3StepMap["GeForce GTX TITAN X"] = std::pair(432, 48); icpStepMap["GeForce GTX 980 Ti"] = std::pair(320, 64); rgbStepMap["GeForce GTX 980 Ti"] = std::pair(128, 96); rgbResMap["GeForce GTX 980 Ti"] = std::pair(224, 384); so3StepMap["GeForce GTX 980 Ti"] = std::pair(432, 48); icpStepMap["GeForce GTX 1070"] = std::pair(64, 240); rgbStepMap["GeForce GTX 1070"] = std::pair(128, 96); rgbResMap["GeForce GTX 1070"] = std::pair(256, 464); so3StepMap["GeForce GTX 1070"] = std::pair(256, 48); if(icpStepMap.find(dev) == icpStepMap.end()) { std::stringstream strs; strs << "Your GPU \"" << dev << "\" isn't in the ICP Step performance database, please add it"; std::cout << strs.str() << std::endl; } else { icpStepThreads = icpStepMap[dev].first; icpStepBlocks = icpStepMap[dev].second; } if(rgbStepMap.find(dev) == rgbStepMap.end()) { std::stringstream strs; strs << "Your GPU \"" << dev << "\" isn't in the RGB Step performance database, please add it"; std::cout << strs.str() << std::endl; } else { rgbStepThreads = rgbStepMap[dev].first; rgbStepBlocks = rgbStepMap[dev].second; } if(rgbResMap.find(dev) == rgbResMap.end()) { std::stringstream strs; strs << "Your GPU \"" << dev << "\" isn't in the RGB Res performance database, please add it"; std::cout << strs.str() << std::endl; } else { rgbResThreads = rgbResMap[dev].first; rgbResBlocks = rgbResMap[dev].second; } if(so3StepMap.find(dev) == so3StepMap.end()) { std::stringstream strs; strs << "Your GPU \"" << dev << "\" isn't in the SO3 Step performance database, please add it"; std::cout << strs.str() << std::endl; } else { so3StepThreads = so3StepMap[dev].first; so3StepBlocks = so3StepMap[dev].second; } } std::map > icpStepMap, rgbStepMap, rgbResMap, so3StepMap; }; #endif /* GPUCONFIG_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/GraphNode.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef GRAPHNODE_H_ #define GRAPHNODE_H_ #include class GraphNode { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW GraphNode() {} int id; Eigen::Vector3f position; Eigen::Matrix3f rotation; Eigen::Vector3f translation; std::vector neighbours; bool enabled; }; #endif /* GRAPHNODE_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Img.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef UTILS_IMG_H_ #define UTILS_IMG_H_ #include template class Img { public: Img(const int rows, const int cols) : rows(rows), cols(cols), data(new unsigned char[rows * cols * sizeof(T)]), owned(true) {} Img(const int rows, const int cols, T * data) : rows(rows), cols(cols), data((unsigned char *)data), owned(false) {} virtual ~Img() { if(owned) { delete [] data; } } const int rows; const int cols; unsigned char * data; const bool owned; template inline V & at(const int i) { return ((V*)data)[i]; } template inline V & at(const int row, const int col) { return ((V*)data)[cols * row + col]; } template inline const V & at(const int row, const int col) const { return ((const V*)data)[cols * row + col]; } }; #endif /* UTILS_IMG_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Intrinsics.cpp ================================================ /* * This file was written for porting ElasticFusion to windows * by Filip Srajer (filip.srajer@inf.ethz.ch). * */ #include "Intrinsics.h" const Intrinsics & Intrinsics::getInstance(float fx,float fy,float cx,float cy) { static const Intrinsics instance(fx,fy,cx,cy); return instance; } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Intrinsics.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef INTRINSICS_H_ #define INTRINSICS_H_ #include #include "../Defines.h" class Intrinsics { public: EFUSION_API static const Intrinsics & getInstance(float fx = 0,float fy = 0,float cx = 0,float cy = 0); const float & fx() const { return fx_; } const float & fy() const { return fy_; } const float & cx() const { return cx_; } const float & cy() const { return cy_; } private: Intrinsics(float fx, float fy, float cx, float cy) : fx_(fx), fy_(fy), cx_(cx), cy_(cy) { assert(fx != 0 && fy != 0 && "You haven't initialised the Intrinsics class!"); } const float fx_, fy_, cx_, cy_; }; #endif /* INTRINSICS_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Jacobian.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef UTILS_JACOBIAN_H_ #define UTILS_JACOBIAN_H_ #include #include "OrderedJacobianRow.h" class Jacobian { public: Jacobian() : columns(0) {} virtual ~Jacobian() { reset(); } void assign(std::vector & rows, const int columns) { reset(); this->rows = rows; this->columns = columns; } int cols() const { return columns; } int nonZero() const { int count = 0; for(size_t i = 0; i < rows.size(); i++) { count += rows[i]->nonZeros(); } return count; } std::vector rows; private: int columns; void reset() { for(size_t i = 0; i < rows.size(); i++) { delete rows[i]; } rows.clear(); } }; #endif /* UTILS_JACOBIAN_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/OdometryProvider.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef ODOMETRYPROVIDER_H_ #define ODOMETRYPROVIDER_H_ #include #include #include class OdometryProvider { public: OdometryProvider() {} virtual ~OdometryProvider() {} static inline Eigen::Matrix rodrigues(const Eigen::Vector3d & src) { Eigen::Matrix dst = Eigen::Matrix::Identity(); double rx, ry, rz, theta; rx = src(0); ry = src(1); rz = src(2); theta = src.norm(); if(theta >= DBL_EPSILON) { const double I[] = { 1, 0, 0, 0, 1, 0, 0, 0, 1 }; double c = cos(theta); double s = sin(theta); double c1 = 1. - c; double itheta = theta ? 1./theta : 0.; rx *= itheta; ry *= itheta; rz *= itheta; double rrt[] = { rx*rx, rx*ry, rx*rz, rx*ry, ry*ry, ry*rz, rx*rz, ry*rz, rz*rz }; double _r_x_[] = { 0, -rz, ry, rz, 0, -rx, -ry, rx, 0 }; double R[9]; for(int k = 0; k < 9; k++) { R[k] = c*I[k] + c1*rrt[k] + s*_r_x_[k]; } memcpy(dst.data(), &R[0], sizeof(Eigen::Matrix)); } return dst; } static inline void computeUpdateSE3(Eigen::Matrix & resultRt, const Eigen::Matrix & result, Eigen::Isometry3f & rgbOdom) { // for infinitesimal transformation Eigen::Matrix Rt = Eigen::Matrix::Identity(); Eigen::Vector3d rvec(result(3), result(4), result(5)); Eigen::Matrix R = rodrigues(rvec); Rt.topLeftCorner(3, 3) = R; Rt(0, 3) = result(0); Rt(1, 3) = result(1); Rt(2, 3) = result(2); resultRt = Rt * resultRt; Eigen::Matrix rotation = resultRt.topLeftCorner(3, 3); rgbOdom.setIdentity(); rgbOdom.rotate(rotation.cast().eval()); rgbOdom.translation() = resultRt.cast().eval().topRightCorner(3, 1); } }; #endif /* ODOMETRYPROVIDER_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/OrderedJacobianRow.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef UTILS_ORDEREDJACOBIANROW_H_ #define UTILS_ORDEREDJACOBIANROW_H_ #include #include class OrderedJacobianRow { public: OrderedJacobianRow(const int nonZeros) : indices(new int[nonZeros]), vals(new double[nonZeros]), lastSlot(0), lastIndex(-1), maxNonZero(nonZeros) {} virtual ~OrderedJacobianRow() { delete [] indices; delete [] vals; } //You have to use this in an ordered fashion for efficiency :) void append(const int index, const double value) { assert(index > lastIndex); indexSlotMap[index] = lastSlot; indices[lastSlot] = index; vals[lastSlot] = value; lastSlot++; lastIndex = index; } //To add to an existing and already weighted value void addTo(const int index, const double value, const double weight) { double & val = vals[indexSlotMap[index]]; val = ((val / weight) + value) * weight; } int nonZeros() { return lastSlot; } int * indices; double * vals; private: int lastSlot; int lastIndex; const int maxNonZero; std::unordered_map indexSlotMap; }; #endif /* UTILS_ORDEREDJACOBIANROW_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Parse.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "Parse.h" Parse::Parse() { } const Parse & Parse::get() { static const Parse instance; return instance; } int Parse::arg(int argc, char** argv, const char* str, std::string &val) const { int index = findArg(argc, argv, str) + 1; if(index > 0 && index < argc) { val = argv[index]; } return index - 1; } int Parse::arg(int argc, char** argv, const char* str, float &val) const { int index = findArg(argc, argv, str) + 1; if(index > 0 && index < argc) { val = atof(argv[index]); } return index - 1; } int Parse::arg(int argc, char** argv, const char* str, int &val) const { int index = findArg(argc, argv, str) + 1; if(index > 0 && index < argc) { val = atoi(argv[index]); } return index - 1; } std::string Parse::shaderDir() const { std::string currentVal = STR(SHADER_DIR); assert(pangolin::FileExists(currentVal) && "Shader directory not found!"); return currentVal; } std::string Parse::baseDir() const { char buf[256]; #ifdef WIN32 int length = GetModuleFileName(NULL,buf,sizeof(buf)); #else int length = readlink("/proc/self/exe",buf,sizeof(buf)); #endif std::string currentVal; currentVal.append((char *)&buf, length); currentVal = currentVal.substr(0, currentVal #ifdef WIN32 .rfind("\\build\\")); #else .rfind("/build/")); #endif return currentVal; } int Parse::findArg(int argc, char** argv, const char* argument_name) const { for(int i = 1; i < argc; ++i) { // Search for the string if(strcmp(argv[i], argument_name) == 0) { return i; } } return -1; } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Parse.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef PARSE_H_ #define PARSE_H_ #ifdef WIN32 # include #else # include #endif #include #include #ifndef WIN32 # include #endif #include #include #include "../Defines.h" #define XSTR(x) #x #define STR(x) XSTR(x) class Parse { public: EFUSION_API static const Parse & get(); EFUSION_API int arg(int argc, char** argv, const char* str, std::string &val) const; EFUSION_API int arg(int argc, char** argv, const char* str, float &val) const; EFUSION_API int arg(int argc, char** argv, const char* str, int &val) const; EFUSION_API std::string shaderDir() const; EFUSION_API std::string baseDir() const; private: EFUSION_API Parse(); EFUSION_API int findArg(int argc,char** argv,const char* argument_name) const; }; #endif /* PARSE_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/RGBDOdometry.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "RGBDOdometry.h" RGBDOdometry::RGBDOdometry(int width, int height, float cx, float cy, float fx, float fy, float distThresh, float angleThresh) : lastICPError(0), lastICPCount(width * height), lastRGBError(0), lastRGBCount(width * height), lastSO3Error(0), lastSO3Count(width * height), lastA(Eigen::Matrix::Zero()), lastb(Eigen::Matrix::Zero()), sobelSize(3), sobelScale(1.0 / pow(2.0, sobelSize)), maxDepthDeltaRGB(0.07), maxDepthRGB(6.0), distThres_(distThresh), angleThres_(angleThresh), width(width), height(height), cx(cx), cy(cy), fx(fx), fy(fy) { sumDataSE3.create(MAX_THREADS); outDataSE3.create(1); sumResidualRGB.create(MAX_THREADS); sumDataSO3.create(MAX_THREADS); outDataSO3.create(1); for(int i = 0; i < NUM_PYRS; i++) { int2 nextDim = {height >> i, width >> i}; pyrDims.push_back(nextDim); } for(int i = 0; i < NUM_PYRS; i++) { lastDepth[i].create(pyrDims.at(i).x, pyrDims.at(i).y); lastImage[i].create(pyrDims.at(i).x, pyrDims.at(i).y); nextDepth[i].create(pyrDims.at(i).x, pyrDims.at(i).y); nextImage[i].create(pyrDims.at(i).x, pyrDims.at(i).y); lastNextImage[i].create(pyrDims.at(i).x, pyrDims.at(i).y); nextdIdx[i].create(pyrDims.at(i).x, pyrDims.at(i).y); nextdIdy[i].create(pyrDims.at(i).x, pyrDims.at(i).y); pointClouds[i].create(pyrDims.at(i).x, pyrDims.at(i).y); corresImg[i].create(pyrDims.at(i).x, pyrDims.at(i).y); } intr.cx = cx; intr.cy = cy; intr.fx = fx; intr.fy = fy; iterations.resize(NUM_PYRS); depth_tmp.resize(NUM_PYRS); vmaps_g_prev_.resize(NUM_PYRS); nmaps_g_prev_.resize(NUM_PYRS); vmaps_curr_.resize(NUM_PYRS); nmaps_curr_.resize(NUM_PYRS); for (int i = 0; i < NUM_PYRS; ++i) { int pyr_rows = height >> i; int pyr_cols = width >> i; depth_tmp[i].create (pyr_rows, pyr_cols); vmaps_g_prev_[i].create (pyr_rows*3, pyr_cols); nmaps_g_prev_[i].create (pyr_rows*3, pyr_cols); vmaps_curr_[i].create (pyr_rows*3, pyr_cols); nmaps_curr_[i].create (pyr_rows*3, pyr_cols); } vmaps_tmp.create(height * 4 * width); nmaps_tmp.create(height * 4 * width); minimumGradientMagnitudes.resize(NUM_PYRS); minimumGradientMagnitudes[0] = 5; minimumGradientMagnitudes[1] = 3; minimumGradientMagnitudes[2] = 1; } RGBDOdometry::~RGBDOdometry() { } void RGBDOdometry::initICP(GPUTexture * filteredDepth, const float depthCutoff) { cudaArray * textPtr; cudaGraphicsMapResources(1, &filteredDepth->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, filteredDepth->cudaRes, 0, 0); cudaMemcpy2DFromArray(depth_tmp[0].ptr(0), depth_tmp[0].step(), textPtr, 0, 0, depth_tmp[0].colsBytes(), depth_tmp[0].rows(), cudaMemcpyDeviceToDevice); cudaGraphicsUnmapResources(1, &filteredDepth->cudaRes); for(int i = 1; i < NUM_PYRS; ++i) { pyrDown(depth_tmp[i - 1], depth_tmp[i]); } for(int i = 0; i < NUM_PYRS; ++i) { createVMap(intr(i), depth_tmp[i], vmaps_curr_[i], depthCutoff); createNMap(vmaps_curr_[i], nmaps_curr_[i]); } cudaDeviceSynchronize(); } void RGBDOdometry::initICP(GPUTexture * predictedVertices, GPUTexture * predictedNormals, const float depthCutoff) { cudaArray * textPtr; cudaGraphicsMapResources(1, &predictedVertices->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, predictedVertices->cudaRes, 0, 0); cudaMemcpyFromArray(vmaps_tmp.ptr(), textPtr, 0, 0, vmaps_tmp.sizeBytes(), cudaMemcpyDeviceToDevice); cudaGraphicsUnmapResources(1, &predictedVertices->cudaRes); cudaGraphicsMapResources(1, &predictedNormals->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, predictedNormals->cudaRes, 0, 0); cudaMemcpyFromArray(nmaps_tmp.ptr(), textPtr, 0, 0, nmaps_tmp.sizeBytes(), cudaMemcpyDeviceToDevice); cudaGraphicsUnmapResources(1, &predictedNormals->cudaRes); copyMaps(vmaps_tmp, nmaps_tmp, vmaps_curr_[0], nmaps_curr_[0]); for(int i = 1; i < NUM_PYRS; ++i) { resizeVMap(vmaps_curr_[i - 1], vmaps_curr_[i]); resizeNMap(nmaps_curr_[i - 1], nmaps_curr_[i]); } cudaDeviceSynchronize(); } void RGBDOdometry::initICPModel(GPUTexture * predictedVertices, GPUTexture * predictedNormals, const float depthCutoff, const Eigen::Matrix4f & modelPose) { cudaArray * textPtr; cudaGraphicsMapResources(1, &predictedVertices->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, predictedVertices->cudaRes, 0, 0); cudaMemcpyFromArray(vmaps_tmp.ptr(), textPtr, 0, 0, vmaps_tmp.sizeBytes(), cudaMemcpyDeviceToDevice); cudaGraphicsUnmapResources(1, &predictedVertices->cudaRes); cudaGraphicsMapResources(1, &predictedNormals->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, predictedNormals->cudaRes, 0, 0); cudaMemcpyFromArray(nmaps_tmp.ptr(), textPtr, 0, 0, nmaps_tmp.sizeBytes(), cudaMemcpyDeviceToDevice); cudaGraphicsUnmapResources(1, &predictedNormals->cudaRes); copyMaps(vmaps_tmp, nmaps_tmp, vmaps_g_prev_[0], nmaps_g_prev_[0]); for(int i = 1; i < NUM_PYRS; ++i) { resizeVMap(vmaps_g_prev_[i - 1], vmaps_g_prev_[i]); resizeNMap(nmaps_g_prev_[i - 1], nmaps_g_prev_[i]); } Eigen::Matrix Rcam = modelPose.topLeftCorner(3, 3); Eigen::Vector3f tcam = modelPose.topRightCorner(3, 1); mat33 device_Rcam = Rcam; float3 device_tcam = *reinterpret_cast(tcam.data()); for(int i = 0; i < NUM_PYRS; ++i) { tranformMaps(vmaps_g_prev_[i], nmaps_g_prev_[i], device_Rcam, device_tcam, vmaps_g_prev_[i], nmaps_g_prev_[i]); } cudaDeviceSynchronize(); } void RGBDOdometry::populateRGBDData(GPUTexture * rgb, DeviceArray2D * destDepths, DeviceArray2D * destImages) { verticesToDepth(vmaps_tmp, destDepths[0], maxDepthRGB); for(int i = 0; i + 1 < NUM_PYRS; i++) { pyrDownGaussF(destDepths[i], destDepths[i + 1]); } cudaArray * textPtr; cudaGraphicsMapResources(1, &rgb->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, rgb->cudaRes, 0, 0); imageBGRToIntensity(textPtr, destImages[0]); cudaGraphicsUnmapResources(1, &rgb->cudaRes); for(int i = 0; i + 1 < NUM_PYRS; i++) { pyrDownUcharGauss(destImages[i], destImages[i + 1]); } cudaDeviceSynchronize(); } void RGBDOdometry::initRGBModel(GPUTexture * rgb) { //NOTE: This depends on vmaps_tmp containing the corresponding depth from initICPModel populateRGBDData(rgb, &lastDepth[0], &lastImage[0]); } void RGBDOdometry::initRGB(GPUTexture * rgb) { //NOTE: This depends on vmaps_tmp containing the corresponding depth from initICP populateRGBDData(rgb, &nextDepth[0], &nextImage[0]); } void RGBDOdometry::initFirstRGB(GPUTexture * rgb) { cudaArray * textPtr; cudaGraphicsMapResources(1, &rgb->cudaRes); cudaGraphicsSubResourceGetMappedArray(&textPtr, rgb->cudaRes, 0, 0); imageBGRToIntensity(textPtr, lastNextImage[0]); cudaGraphicsUnmapResources(1, &rgb->cudaRes); for(int i = 0; i + 1 < NUM_PYRS; i++) { pyrDownUcharGauss(lastNextImage[i], lastNextImage[i + 1]); } } void RGBDOdometry::getIncrementalTransformation(Eigen::Vector3f & trans, Eigen::Matrix & rot, const bool & rgbOnly, const float & icpWeight, const bool & pyramid, const bool & fastOdom, const bool & so3) { bool icp = !rgbOnly && icpWeight > 0; bool rgb = rgbOnly || icpWeight < 100; Eigen::Matrix Rprev = rot; Eigen::Vector3f tprev = trans; Eigen::Matrix Rcurr = Rprev; Eigen::Vector3f tcurr = tprev; if(rgb) { for(int i = 0; i < NUM_PYRS; i++) { computeDerivativeImages(nextImage[i], nextdIdx[i], nextdIdy[i]); } } Eigen::Matrix resultR = Eigen::Matrix::Identity(); if(so3) { int pyramidLevel = 2; Eigen::Matrix R_lr = Eigen::Matrix::Identity(); Eigen::Matrix K = Eigen::Matrix::Zero(); K(0, 0) = intr(pyramidLevel).fx; K(1, 1) = intr(pyramidLevel).fy; K(0, 2) = intr(pyramidLevel).cx; K(1, 2) = intr(pyramidLevel).cy; K(2, 2) = 1; float lastError = std::numeric_limits::max() / 2; float lastCount = std::numeric_limits::max() / 2; Eigen::Matrix lastResultR = Eigen::Matrix::Identity(); for(int i = 0; i < 10; i++) { Eigen::Matrix jtj; Eigen::Matrix jtr; Eigen::Matrix homography = K * resultR * K.inverse(); mat33 imageBasis; memcpy(&imageBasis.data[0], homography.cast().eval().data(), sizeof(mat33)); Eigen::Matrix K_inv = K.inverse(); mat33 kinv; memcpy(&kinv.data[0], K_inv.cast().eval().data(), sizeof(mat33)); Eigen::Matrix K_R_lr = K * resultR; mat33 krlr; memcpy(&krlr.data[0], K_R_lr.cast().eval().data(), sizeof(mat33)); float residual[2]; TICK("so3Step"); so3Step(lastNextImage[pyramidLevel], nextImage[pyramidLevel], imageBasis, kinv, krlr, sumDataSO3, outDataSO3, jtj.data(), jtr.data(), &residual[0], GPUConfig::getInstance().so3StepThreads, GPUConfig::getInstance().so3StepBlocks); TOCK("so3Step"); lastSO3Error = sqrt(residual[0]) / residual[1]; lastSO3Count = residual[1]; //Converged if(lastSO3Error < lastError && lastCount == lastSO3Count) { break; } else if(lastSO3Error > lastError + 0.001) //Diverging { lastSO3Error = lastError; lastSO3Count = lastCount; resultR = lastResultR; break; } lastError = lastSO3Error; lastCount = lastSO3Count; lastResultR = resultR; Eigen::Vector3f delta = jtj.ldlt().solve(jtr); Eigen::Matrix rotUpdate = OdometryProvider::rodrigues(delta.cast()); R_lr = rotUpdate.cast() * R_lr; for(int x = 0; x < 3; x++) { for(int y = 0; y < 3; y++) { resultR(x, y) = R_lr(x, y); } } } } iterations[0] = fastOdom ? 3 : 10; iterations[1] = pyramid ? 5 : 0; iterations[2] = pyramid ? 4 : 0; Eigen::Matrix Rprev_inv = Rprev.inverse(); mat33 device_Rprev_inv = Rprev_inv; float3 device_tprev = *reinterpret_cast(tprev.data()); Eigen::Matrix resultRt = Eigen::Matrix::Identity(); if(so3) { for(int x = 0; x < 3; x++) { for(int y = 0; y < 3; y++) { resultRt(x, y) = resultR(x, y); } } } for(int i = NUM_PYRS - 1; i >= 0; i--) { if(rgb) { projectToPointCloud(lastDepth[i], pointClouds[i], intr, i); } Eigen::Matrix K = Eigen::Matrix::Zero(); K(0, 0) = intr(i).fx; K(1, 1) = intr(i).fy; K(0, 2) = intr(i).cx; K(1, 2) = intr(i).cy; K(2, 2) = 1; lastRGBError = std::numeric_limits::max(); for(int j = 0; j < iterations[i]; j++) { Eigen::Matrix Rt = resultRt.inverse(); Eigen::Matrix R = Rt.topLeftCorner(3, 3); Eigen::Matrix KRK_inv = K * R * K.inverse(); mat33 krkInv; memcpy(&krkInv.data[0], KRK_inv.cast().eval().data(), sizeof(mat33)); Eigen::Vector3d Kt = Rt.topRightCorner(3, 1); Kt = K * Kt; float3 kt = {(float)Kt(0), (float)Kt(1), (float)Kt(2)}; int sigma = 0; int rgbSize = 0; if(rgb) { TICK("computeRgbResidual"); computeRgbResidual(pow(minimumGradientMagnitudes[i], 2.0) / pow(sobelScale, 2.0), nextdIdx[i], nextdIdy[i], lastDepth[i], nextDepth[i], lastImage[i], nextImage[i], corresImg[i], sumResidualRGB, maxDepthDeltaRGB, kt, krkInv, sigma, rgbSize, GPUConfig::getInstance().rgbResThreads, GPUConfig::getInstance().rgbResBlocks); TOCK("computeRgbResidual"); } float sigmaVal = std::sqrt((float)sigma / rgbSize == 0 ? 1 : rgbSize); float rgbError = std::sqrt(sigma) / (rgbSize == 0 ? 1 : rgbSize); if(rgbOnly && rgbError > lastRGBError) { break; } lastRGBError = rgbError; lastRGBCount = rgbSize; if(rgbOnly) { sigmaVal = -1; //Signals the internal optimisation to weight evenly } Eigen::Matrix A_icp; Eigen::Matrix b_icp; mat33 device_Rcurr = Rcurr; float3 device_tcurr = *reinterpret_cast(tcurr.data()); DeviceArray2D& vmap_curr = vmaps_curr_[i]; DeviceArray2D& nmap_curr = nmaps_curr_[i]; DeviceArray2D& vmap_g_prev = vmaps_g_prev_[i]; DeviceArray2D& nmap_g_prev = nmaps_g_prev_[i]; float residual[2]; if(icp) { TICK("icpStep"); icpStep(device_Rcurr, device_tcurr, vmap_curr, nmap_curr, device_Rprev_inv, device_tprev, intr(i), vmap_g_prev, nmap_g_prev, distThres_, angleThres_, sumDataSE3, outDataSE3, A_icp.data(), b_icp.data(), &residual[0], GPUConfig::getInstance().icpStepThreads, GPUConfig::getInstance().icpStepBlocks); TOCK("icpStep"); } lastICPError = sqrt(residual[0]) / residual[1]; lastICPCount = residual[1]; Eigen::Matrix A_rgbd; Eigen::Matrix b_rgbd; if(rgb) { TICK("rgbStep"); rgbStep(corresImg[i], sigmaVal, pointClouds[i], intr(i).fx, intr(i).fy, nextdIdx[i], nextdIdy[i], sobelScale, sumDataSE3, outDataSE3, A_rgbd.data(), b_rgbd.data(), GPUConfig::getInstance().rgbStepThreads, GPUConfig::getInstance().rgbStepBlocks); TOCK("rgbStep"); } Eigen::Matrix result; Eigen::Matrix dA_rgbd = A_rgbd.cast(); Eigen::Matrix dA_icp = A_icp.cast(); Eigen::Matrix db_rgbd = b_rgbd.cast(); Eigen::Matrix db_icp = b_icp.cast(); if(icp && rgb) { double w = icpWeight; lastA = dA_rgbd + w * w * dA_icp; lastb = db_rgbd + w * db_icp; result = lastA.ldlt().solve(lastb); } else if(icp) { lastA = dA_icp; lastb = db_icp; result = lastA.ldlt().solve(lastb); } else if(rgb) { lastA = dA_rgbd; lastb = db_rgbd; result = lastA.ldlt().solve(lastb); } else { assert(false && "Control shouldn't reach here"); } Eigen::Isometry3f rgbOdom; OdometryProvider::computeUpdateSE3(resultRt, result, rgbOdom); Eigen::Isometry3f currentT; currentT.setIdentity(); currentT.rotate(Rprev); currentT.translation() = tprev; currentT = currentT * rgbOdom.inverse(); tcurr = currentT.translation(); Rcurr = currentT.rotation(); } } if(rgb && (tcurr - tprev).norm() > 0.3) { Rcurr = Rprev; tcurr = tprev; } if(so3) { for(int i = 0; i < NUM_PYRS; i++) { std::swap(lastNextImage[i], nextImage[i]); } } trans = tcurr; rot = Rcurr; } void RGBDOdometry::getIncrementalTransformation_withseg(Eigen::Vector3f & trans, Eigen::Matrix & rot, const bool & rgbOnly, const float & weight_rgb, const float & weight_seg, const float & icpWeight, const bool & pyramid, const bool & fastOdom, const bool & so3) { bool icp = !rgbOnly && icpWeight > 0; bool rgb = rgbOnly || icpWeight < 100; Eigen::Matrix Rprev = rot; Eigen::Vector3f tprev = trans; Eigen::Matrix Rcurr = Rprev; Eigen::Vector3f tcurr = tprev; if(rgb) { for(int i = 0; i < NUM_PYRS; i++) { computeDerivativeImages(nextImage[i], nextdIdx[i], nextdIdy[i]); } } Eigen::Matrix resultR = Eigen::Matrix::Identity(); if(so3) { int pyramidLevel = 2; Eigen::Matrix R_lr = Eigen::Matrix::Identity(); Eigen::Matrix K = Eigen::Matrix::Zero(); K(0, 0) = intr(pyramidLevel).fx; K(1, 1) = intr(pyramidLevel).fy; K(0, 2) = intr(pyramidLevel).cx; K(1, 2) = intr(pyramidLevel).cy; K(2, 2) = 1; float lastError = std::numeric_limits::max() / 2; float lastCount = std::numeric_limits::max() / 2; Eigen::Matrix lastResultR = Eigen::Matrix::Identity(); for(int i = 0; i < 10; i++) { Eigen::Matrix jtj; Eigen::Matrix jtr; Eigen::Matrix homography = K * resultR * K.inverse(); mat33 imageBasis; memcpy(&imageBasis.data[0], homography.cast().eval().data(), sizeof(mat33)); Eigen::Matrix K_inv = K.inverse(); mat33 kinv; memcpy(&kinv.data[0], K_inv.cast().eval().data(), sizeof(mat33)); Eigen::Matrix K_R_lr = K * resultR; mat33 krlr; memcpy(&krlr.data[0], K_R_lr.cast().eval().data(), sizeof(mat33)); float residual[2]; TICK("so3Step"); so3Step(lastNextImage[pyramidLevel], nextImage[pyramidLevel], imageBasis, kinv, krlr, sumDataSO3, outDataSO3, jtj.data(), jtr.data(), &residual[0], GPUConfig::getInstance().so3StepThreads, GPUConfig::getInstance().so3StepBlocks); TOCK("so3Step"); lastSO3Error = sqrt(residual[0]) / residual[1]; lastSO3Count = residual[1]; //Converged if(lastSO3Error < lastError && lastCount == lastSO3Count) { break; } else if(lastSO3Error > lastError + 0.001) //Diverging { lastSO3Error = lastError; lastSO3Count = lastCount; resultR = lastResultR; break; } lastError = lastSO3Error; lastCount = lastSO3Count; lastResultR = resultR; Eigen::Vector3f delta = jtj.ldlt().solve(jtr); Eigen::Matrix rotUpdate = OdometryProvider::rodrigues(delta.cast()); R_lr = rotUpdate.cast() * R_lr; for(int x = 0; x < 3; x++) { for(int y = 0; y < 3; y++) { resultR(x, y) = R_lr(x, y); } } } } iterations[0] = fastOdom ? 3 : 10; iterations[1] = pyramid ? 5 : 0; iterations[2] = pyramid ? 4 : 0; Eigen::Matrix Rprev_inv = Rprev.inverse(); mat33 device_Rprev_inv = Rprev_inv; float3 device_tprev = *reinterpret_cast(tprev.data()); Eigen::Matrix resultRt = Eigen::Matrix::Identity(); if(so3) { for(int x = 0; x < 3; x++) { for(int y = 0; y < 3; y++) { resultRt(x, y) = resultR(x, y); } } } for(int i = NUM_PYRS - 1; i >= 0; i--) { if(rgb) { projectToPointCloud(lastDepth[i], pointClouds[i], intr, i); } Eigen::Matrix K = Eigen::Matrix::Zero(); K(0, 0) = intr(i).fx; K(1, 1) = intr(i).fy; K(0, 2) = intr(i).cx; K(1, 2) = intr(i).cy; K(2, 2) = 1; lastRGBError = std::numeric_limits::max(); for(int j = 0; j < iterations[i]; j++) { Eigen::Matrix Rt = resultRt.inverse(); Eigen::Matrix R = Rt.topLeftCorner(3, 3); Eigen::Matrix KRK_inv = K * R * K.inverse(); mat33 krkInv; memcpy(&krkInv.data[0], KRK_inv.cast().eval().data(), sizeof(mat33)); Eigen::Vector3d Kt = Rt.topRightCorner(3, 1); Kt = K * Kt; float3 kt = {(float)Kt(0), (float)Kt(1), (float)Kt(2)}; int sigma = 0; int rgbSize = 0; if(rgb) { TICK("computeRgbResidual"); computeRgbResidual(pow(minimumGradientMagnitudes[i], 2.0) / pow(sobelScale, 2.0), nextdIdx[i], nextdIdy[i], lastDepth[i], nextDepth[i], lastImage[i], nextImage[i], corresImg[i], sumResidualRGB, maxDepthDeltaRGB, kt, krkInv, sigma, rgbSize, GPUConfig::getInstance().rgbResThreads, GPUConfig::getInstance().rgbResBlocks); TOCK("computeRgbResidual"); } float sigmaVal = std::sqrt((float)sigma / rgbSize == 0 ? 1 : rgbSize); float rgbError = std::sqrt(sigma) / (rgbSize == 0 ? 1 : rgbSize); if(rgbOnly && rgbError > lastRGBError) { break; } lastRGBError = rgbError; lastRGBCount = rgbSize; if(rgbOnly) { sigmaVal = -1; //Signals the internal optimisation to weight evenly } Eigen::Matrix A_icp; Eigen::Matrix b_icp; mat33 device_Rcurr = Rcurr; float3 device_tcurr = *reinterpret_cast(tcurr.data()); DeviceArray2D& vmap_curr = vmaps_curr_[i]; DeviceArray2D& nmap_curr = nmaps_curr_[i]; DeviceArray2D& vmap_g_prev = vmaps_g_prev_[i]; DeviceArray2D& nmap_g_prev = nmaps_g_prev_[i]; float residual[2]; if(icp) { TICK("icpStep"); icpStep(device_Rcurr, device_tcurr, vmap_curr, nmap_curr, device_Rprev_inv, device_tprev, intr(i), vmap_g_prev, nmap_g_prev, distThres_, angleThres_, sumDataSE3, outDataSE3, A_icp.data(), b_icp.data(), &residual[0], GPUConfig::getInstance().icpStepThreads, GPUConfig::getInstance().icpStepBlocks); TOCK("icpStep"); } lastICPError = sqrt(residual[0]) / residual[1]; lastICPCount = residual[1]; Eigen::Matrix A_rgbd; Eigen::Matrix b_rgbd; if(rgb) { TICK("rgbStep"); rgbStep(corresImg[i], sigmaVal, pointClouds[i], intr(i).fx, intr(i).fy, nextdIdx[i], nextdIdy[i], sobelScale, sumDataSE3, outDataSE3, A_rgbd.data(), b_rgbd.data(), GPUConfig::getInstance().rgbStepThreads, GPUConfig::getInstance().rgbStepBlocks); TOCK("rgbStep"); } Eigen::Matrix result; Eigen::Matrix dA_rgbd = A_rgbd.cast(); Eigen::Matrix dA_icp = A_icp.cast(); Eigen::Matrix db_rgbd = b_rgbd.cast(); Eigen::Matrix db_icp = b_icp.cast(); if(icp && rgb) { double w = icpWeight; lastA = dA_rgbd + w * w * dA_icp; lastb = db_rgbd + w * db_icp; result = lastA.ldlt().solve(lastb); } else if(icp) { lastA = dA_icp; lastb = db_icp; result = lastA.ldlt().solve(lastb); } else if(rgb) { lastA = dA_rgbd; lastb = db_rgbd; result = lastA.ldlt().solve(lastb); } else { assert(false && "Control shouldn't reach here"); } Eigen::Isometry3f rgbOdom; OdometryProvider::computeUpdateSE3(resultRt, result, rgbOdom); Eigen::Isometry3f currentT; currentT.setIdentity(); currentT.rotate(Rprev); currentT.translation() = tprev; currentT = currentT * rgbOdom.inverse(); tcurr = currentT.translation(); Rcurr = currentT.rotation(); } } if(rgb && (tcurr - tprev).norm() > 0.3) { Rcurr = Rprev; tcurr = tprev; } if(so3) { for(int i = 0; i < NUM_PYRS; i++) { std::swap(lastNextImage[i], nextImage[i]); } } trans = tcurr; rot = Rcurr; } Eigen::MatrixXd RGBDOdometry::getCovariance() { return lastA.cast().lu().inverse(); } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/RGBDOdometry.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef RGBDODOMETRY_H_ #define RGBDODOMETRY_H_ #include "Stopwatch.h" #include "../GPUTexture.h" #include "../Cuda/cudafuncs.cuh" #include "OdometryProvider.h" #include "GPUConfig.h" #include #include class RGBDOdometry { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW RGBDOdometry(int width, int height, float cx, float cy, float fx, float fy, float distThresh = 0.10f, float angleThresh = sin(20.f * 3.14159254f / 180.f)); virtual ~RGBDOdometry(); void initICP(GPUTexture * filteredDepth, const float depthCutoff); void initICP(GPUTexture * predictedVertices, GPUTexture * predictedNormals, const float depthCutoff); void initICPModel(GPUTexture * predictedVertices, GPUTexture * predictedNormals, const float depthCutoff, const Eigen::Matrix4f & modelPose); void initRGB(GPUTexture * rgb); void initRGBModel(GPUTexture * rgb); void initFirstRGB(GPUTexture * rgb); void getIncrementalTransformation(Eigen::Vector3f & trans, Eigen::Matrix & rot, const bool & rgbOnly, const float & icpWeight, const bool & pyramid, const bool & fastOdom, const bool & so3); void getIncrementalTransformation_withseg(Eigen::Vector3f & trans, Eigen::Matrix & rot, const bool & rgbOnly, const float & weight_rgb, const float & weight_seg, const float & icpWeight, const bool & pyramid, const bool & fastOdom, const bool & so3); Eigen::MatrixXd getCovariance(); float lastICPError; float lastICPCount; float lastRGBError; float lastRGBCount; float lastSO3Error; float lastSO3Count; Eigen::Matrix lastA; Eigen::Matrix lastb; private: void populateRGBDData(GPUTexture * rgb, DeviceArray2D * destDepths, DeviceArray2D * destImages); std::vector > depth_tmp; DeviceArray vmaps_tmp; DeviceArray nmaps_tmp; std::vector > vmaps_g_prev_; std::vector > nmaps_g_prev_; std::vector > vmaps_curr_; std::vector > nmaps_curr_; CameraModel intr; DeviceArray sumDataSE3; DeviceArray outDataSE3; DeviceArray sumResidualRGB; DeviceArray sumDataSO3; DeviceArray outDataSO3; const int sobelSize; const float sobelScale; const float maxDepthDeltaRGB; const float maxDepthRGB; std::vector pyrDims; static const int NUM_PYRS = 3; DeviceArray2D lastDepth[NUM_PYRS]; DeviceArray2D lastImage[NUM_PYRS]; DeviceArray2D nextDepth[NUM_PYRS]; DeviceArray2D nextImage[NUM_PYRS]; DeviceArray2D nextdIdx[NUM_PYRS]; DeviceArray2D nextdIdy[NUM_PYRS]; DeviceArray2D lastNextImage[NUM_PYRS]; DeviceArray2D corresImg[NUM_PYRS]; DeviceArray2D pointClouds[NUM_PYRS]; std::vector iterations; std::vector minimumGradientMagnitudes; float distThres_; float angleThres_; Eigen::Matrix lastCov; const int width; const int height; const float cx, cy, fx, fy; }; #endif /* RGBDODOMETRY_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Resolution.cpp ================================================ /* * This file was written for porting ElasticFusion to windows * by Filip Srajer (filip.srajer@inf.ethz.ch). * */ #include "Resolution.h" const Resolution & Resolution::getInstance(int width,int height) { static const Resolution instance(width,height); return instance; } ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Resolution.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef RESOLUTION_H_ #define RESOLUTION_H_ #include #include "../Defines.h" class Resolution { public: EFUSION_API static const Resolution & getInstance(int width = 0,int height = 0); const int & width() const { return imgWidth; } const int & height() const { return imgHeight; } const int & cols() const { return imgWidth; } const int & rows() const { return imgHeight; } const int & numPixels() const { return imgNumPixels; } private: Resolution(int width, int height) : imgWidth(width), imgHeight(height), imgNumPixels(width * height) { assert(width > 0 && height > 0 && "You haven't initialised the Resolution class!"); } const int imgWidth; const int imgHeight; const int imgNumPixels; }; #endif /* RESOLUTION_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/Stopwatch.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef STOPWATCH_H_ #define STOPWATCH_H_ #include #include #ifdef WIN32 # define far # include # include # include // portable: uint64_t MSVC: __int64 # include # include "WindowsExtras.h" #else # include # include # include #endif #include #include #include #include #include #ifndef WIN32 # include # include #endif #include "../Defines.h" #define SEND_INTERVAL_MS 10000 #ifdef WIN32 typedef char stopwatchPacketType; #else typedef unsigned char stopwatchPacketType; #endif #ifndef DISABLE_STOPWATCH #define STOPWATCH(name, expression) \ do \ { \ const unsigned long long int startTime = Stopwatch::getInstance().getCurrentSystemTime(); \ expression \ const unsigned long long int endTime = Stopwatch::getInstance().getCurrentSystemTime(); \ Stopwatch::getInstance().addStopwatchTiming(name, endTime - startTime); \ } \ while(false) #define TICK(name) \ do \ { \ Stopwatch::getInstance().tick(name, Stopwatch::getInstance().getCurrentSystemTime()); \ } \ while(false) #define TOCK(name) \ do \ { \ Stopwatch::getInstance().tock(name, Stopwatch::getInstance().getCurrentSystemTime()); \ } \ while(false) #else #define STOPWATCH(name, expression) \ expression #define TOCK(name) ((void)0) #define TICK(name) ((void)0) #endif class Stopwatch { public: static Stopwatch & getInstance() { static Stopwatch instance; return instance; } void addStopwatchTiming(std::string name, unsigned long long int duration) { if(duration > 0) { timings[name] = (float)(duration) / 1000.0f; } } void setCustomSignature(unsigned long long int newSignature) { signature = newSignature; } const std::map & getTimings() { return timings; } void printAll() { for(std::map::const_iterator it = timings.begin(); it != timings.end(); it++) { std::cout << it->first << ": " << it->second << "ms" << std::endl; } std::cout << std::endl; } void pulse(std::string name) { timings[name] = 1; } void sendAll() { gettimeofday(&clock, 0); if((currentSend = (clock.tv_sec * 1000000 + clock.tv_usec)) - lastSend > SEND_INTERVAL_MS) { int size = 0; stopwatchPacketType * data = serialiseTimings(size); sendto(sockfd, data, size, 0, (struct sockaddr *) &servaddr, sizeof(servaddr)); free(data); lastSend = currentSend; } } static unsigned long long int getCurrentSystemTime() { timeval tv; gettimeofday(&tv, 0); unsigned long long int time = (unsigned long long int)(tv.tv_sec * 1000000 + tv.tv_usec); return time; } void tick(std::string name, unsigned long long int start) { tickTimings[name] = start; } void tock(std::string name, unsigned long long int end) { float duration = (float)(end - tickTimings[name]) / 1000.0f; if(duration > 0) { timings[name] = duration; } } private: Stopwatch() { memset(&servaddr, 0, sizeof(servaddr)); servaddr.sin_family = AF_INET; servaddr.sin_addr.s_addr = inet_addr("127.0.0.1"); servaddr.sin_port = htons(45454); sockfd = socket(AF_INET, SOCK_DGRAM, 0); gettimeofday(&clock, 0); signature = clock.tv_sec * 1000000 + clock.tv_usec; currentSend = lastSend = clock.tv_sec * 1000000 + clock.tv_usec; } virtual ~Stopwatch() { #ifdef WIN32 closesocket(sockfd); #else close(sockfd); #endif } stopwatchPacketType * serialiseTimings(int & packetSize) { packetSize = sizeof(int) + sizeof(unsigned long long int); for(std::map::const_iterator it = timings.begin(); it != timings.end(); it++) { packetSize += it->first.length() + 1 + sizeof(float); } int * dataPacket = (int *)calloc(packetSize, sizeof(unsigned char)); dataPacket[0] = packetSize * sizeof(unsigned char); *((unsigned long long int *)&dataPacket[1]) = signature; float * valuePointer = (float *)&((unsigned long long int *)&dataPacket[1])[1]; for(std::map::const_iterator it = timings.begin(); it != timings.end(); it++) { valuePointer = (float *)mempcpy(valuePointer, it->first.c_str(), it->first.length() + 1); *valuePointer++ = it->second; } return (stopwatchPacketType *)dataPacket; } timeval clock; long long int currentSend, lastSend; unsigned long long int signature; int sockfd; struct sockaddr_in servaddr; std::map timings; std::map tickTimings; }; #endif /* STOPWATCH_H_ */ ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/WindowsExtras.cpp ================================================ /* * This file was written for porting ElasticFusion to windows * by Filip Srajer (filip.srajer@inf.ethz.ch). * */ #include "WindowsExtras.h" #ifdef WIN32 #include #include #define far #include #include int gettimeofday(struct timeval * tp,struct timezone * tzp) { // Note: some broken versions only have 8 trailing zero's, the correct epoch has 9 trailing zero's static const uint64_t EPOCH = ((uint64_t)116444736000000000ULL); SYSTEMTIME system_time; FILETIME file_time; uint64_t time; GetSystemTime(&system_time); SystemTimeToFileTime(&system_time,&file_time); time = ((uint64_t)file_time.dwLowDateTime); time += ((uint64_t)file_time.dwHighDateTime) << 32; tp->tv_sec = (long)((time - EPOCH) / 10000000L); tp->tv_usec = (long)(system_time.wMilliseconds * 1000); return 0; } void *mempcpy(void *dest,const void *src,size_t n) { return (char *)memcpy(dest,src,n) + n; } #endif // WIN32 ================================================ FILE: obj_pose_est/mapping/Core/src/Utils/WindowsExtras.h ================================================ /* * This file was written for porting ElasticFusion to windows * by Filip Srajer (filip.srajer@inf.ethz.ch). * */ #pragma once #include "../Defines.h" #ifdef WIN32 EFUSION_API int gettimeofday(struct timeval * tp,struct timezone * tzp); EFUSION_API void *mempcpy(void *dest,const void *src,size_t n); #endif // WIN32 ================================================ FILE: obj_pose_est/mapping/LICENSE.txt ================================================ WE (Imperial College of Science, Technology and Medicine, (“Imperial College London”)) ARE WILLING TO LICENSE THIS SOFTWARE TO YOU (a licensee “You”) ONLY ON THE CONDITION THAT YOU ACCEPT ALL OF THE TERMS CONTAINED IN THE FOLLOWING AGREEMENT. PLEASE READ THE AGREEMENT CAREFULLY BEFORE DOWNLOADING THE SOFTWARE. BY EXERCISING THE OPTION TO DOWNLOAD THE SOFTWARE YOU AGREE TO BE BOUND BY THE TERMS OF THE AGREEMENT. SOFTWARE LICENSE AGREEMENT (EXCLUDING BSD COMPONENTS) 1. This Agreement pertains to a worldwide, non-exclusive, temporary, fully paid-up, royalty free, non-transferable, non-sub- licensable license (the “License”) to use the ElasticFusion source code, including any modification, part or derivative (the “Software”). Ownership and License. Your rights to use and download the Software onto your computer, and all other copies that You are authorised to make, are specified in this Agreement. However, we (or our licensors) retain all rights, including but not limited to all copyright and other intellectual property rights anywhere in the world, in the Software not expressly granted to You in this Agreement. 2. Permitted use of the License: (a) You may download and install the Software onto one computer or server for use in accordance with Clause 2(b) of this Agreement provided that You ensure that the Software is not accessible by other users unless they have themselves accepted the terms of this license agreement. (b) You may use the Software solely for non-commercial, internal or academic research purposes and only in accordance with the terms of this Agreement. You may not use the Software for commercial purposes, including but not limited to (1) integration of all or part of the source code or the Software into a product for sale or license by or on behalf of You to third parties or (2) use of the Software or any derivative of it for research to develop software products for sale or license to a third party or (3) use of the Software or any derivative of it for research to develop non-software products for sale or license to a third party, or (4) use of the Software to provide any service to an external organisation for which payment is received. Should You wish to use the Software for commercial purposes, You shall email researchcontracts.engineering@imperial.ac.uk. (c) Right to Copy. You may copy the Software for back-up and archival purposes, provided that each copy is kept in your possession and provided You reproduce our copyright notice (set out in Schedule 1) on each copy. (d) Transfer and sub-licensing. You may not rent, lend, or lease the Software and You may not transmit, transfer or sub-license this license to use the Software or any of your rights or obligations under this Agreement to another party. (e) Identity of Licensee. The license granted herein is personal to You. You shall not permit any third party to access, modify or otherwise use the Software nor shall You access modify or otherwise use the Software on behalf of any third party. If You wish to obtain a license for mutiple users or a site license for the Software please contact us at researchcontracts.engineering@imperial.ac.uk. (f) Publications and presentations. You may make public, results or data obtained from, dependent on or arising from research carried out using the Software, provided that any such presentation or publication identifies the Software as the source of the results or the data, including the Copyright Notice given in each element of the Software, and stating that the Software has been made available for use by You under license from Imperial College London and You provide a copy of any such publication to Imperial College London. 3. Prohibited Uses. You may not, without written permission from us at researchcontracts.engineering@imperial.ac.uk: (a) Use, copy, modify, merge, or transfer copies of the Software or any documentation provided by us which relates to the Software except as provided in this Agreement; (b) Use any back-up or archival copies of the Software (or allow anyone else to use such copies) for any purpose other than to replace the original copy in the event it is destroyed or becomes defective; or (c) Disassemble, decompile or "unlock", reverse translate, or in any manner decode the Software for any reason. 4. Warranty Disclaimer (a) Disclaimer. The Software has been developed for research purposes only. You acknowledge that we are providing the Software to You under this license agreement free of charge and on condition that the disclaimer set out below shall apply. We do not represent or warrant that the Software as to: (i) the quality, accuracy or reliability of the Software; (ii) the suitability of the Software for any particular use or for use under any specific conditions; and (iii) whether use of the Software will infringe third-party rights. You acknowledge that You have reviewed and evaluated the Software to determine that it meets your needs and that You assume all responsibility and liability for determining the suitability of the Software as fit for your particular purposes and requirements. Subject to Clause 4(b), we exclude and expressly disclaim all express and implied representations, warranties, conditions and terms not stated herein (including the implied conditions or warranties of satisfactory quality, merchantable quality, merchantability and fitness for purpose). (b) Savings. Some jurisdictions may imply warranties, conditions or terms or impose obligations upon us which cannot, in whole or in part, be excluded, restricted or modified or otherwise do not allow the exclusion of implied warranties, conditions or terms, in which case the above warranty disclaimer and exclusion will only apply to You to the extent permitted in the relevant jurisdiction and does not in any event exclude any implied warranties, conditions or terms which may not under applicable law be excluded. (c) Imperial College London disclaims all responsibility for the use which is made of the Software and any liability for the outcomes arising from using the Software. 5. Limitation of Liability (a) You acknowledge that we are providing the Software to You under this license agreement free of charge and on condition that the limitation of liability set out below shall apply. Accordingly, subject to Clause 5(b), we exclude all liability whether in contract, tort, negligence or otherwise, in respect of the Software and/or any related documentation provided to You by us including, but not limited to, liability for loss or corruption of data, loss of contracts, loss of income, loss of profits, loss of cover and any consequential or indirect loss or damage of any kind arising out of or in connection with this license agreement, however caused. This exclusion shall apply even if we have been advised of the possibility of such loss or damage. (b) You agree to indemnify Imperial College London and hold it harmless from and against any and all claims, damages and liabilities asserted by third parties (including claims for negligence) which arise directly or indirectly from the use of the Software or any derivative of it or the sale of any products based on the Software. You undertake to make no liability claim against any employee, student, agent or appointee of Imperial College London, in connection with this License or the Software. (c) Nothing in this Agreement shall have the effect of excluding or limiting our statutory liability. (d) Some jurisdictions do not allow these limitations or exclusions either wholly or in part, and, to that extent, they may not apply to you. Nothing in this license agreement will affect your statutory rights or other relevant statutory provisions which cannot be excluded, restricted or modified, and its terms and conditions must be read and construed subject to any such statutory rights and/or provisions. 6. Confidentiality. You agree not to disclose any confidential information provided to You by us pursuant to this Agreement to any third party without our prior written consent. The obligations in this Clause 6 shall survive the termination of this Agreement for any reason. 7. Termination. (a) We may terminate this license agreement and your right to use the Software at any time with immediate effect upon written notice to You. (b) This license agreement and your right to use the Software automatically terminate if You: (i) fail to comply with any provisions of this Agreement; or (ii) destroy the copies of the Software in your possession, or voluntarily return the Software to us. (c) Upon termination You will destroy all copies of the Software. (d) Otherwise, the restrictions on your rights to use the Software will expire 10 (ten) years after first use of the Software under this license agreement. 8. Miscellaneous Provisions. (a) This Agreement will be governed by and construed in accordance with the substantive laws of England and Wales whose courts shall have exclusive jurisdiction over all disputes which may arise between us. (b) This is the entire agreement between us relating to the Software, and supersedes any prior purchase order, communications, advertising or representations concerning the Software. (c) No change or modification of this Agreement will be valid unless it is in writing, and is signed by us. (d) The unenforceability or invalidity of any part of this Agreement will not affect the enforceability or validity of the remaining parts. BSD Elements of the Software For BSD elements of the Software, the following terms shall apply: Copyright as indicated in the header of the individual element of the Software. All rights reserved. Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. Schedule 1 The Software ElasticFusion is a Real-time dense visual SLAM system capable of capturing comprehensive dense globally consistent surfel-based maps of room scale environments explored using an RGB-D camera. It is based on the techniques described in the following publication: ElasticFusion: Dense SLAM Without A Pose Graph, T. Whelan, S. Leutenegger, R. F. Salas-Moreno, B. Glocker and A. J. Davison, RSS '15 Copyright Notice This file is part of ElasticFusion. Copyright (C) 2015 Imperial College London The use of the code within this file and all code within files that make up the software that is ElasticFusion is permitted for non-commercial purposes only. The full terms and conditions that apply to the code within this file are detailed within the LICENSE.txt file and at unless explicitly stated. By downloading this file you agree to comply with these terms. If you wish to use any of this code for commercial purposes then please email researchcontracts.engineering@imperial.ac.uk. Acknowledgements If You use the software You should reference the following paper in any publication: ElasticFusion: Dense SLAM Without A Pose Graph, T. Whelan, S. Leutenegger, R. F. Salas-Moreno, B. Glocker and A. J. Davison, RSS '15 ================================================ FILE: obj_pose_est/mapping/README.md ================================================ # 3D Mapping # This is an implementation of 3D mapping in [Object-RPE](https://sites.google.com/view/object-rpe) based on the work of [ElasticFusion](https://github.com/mp3guy/ElasticFusion). ## 1. What do I need to build it? # * Ubuntu 16.04 (Though many other linux distros will work fine) * CMake * OpenGL * [CUDA >= 7.0](https://developer.nvidia.com/cuda-downloads) * OpenCV 3.1 * [OpenNI2](https://github.com/occipital/OpenNI2) * SuiteSparse * Eigen * zlib * libjpeg * [Pangolin](https://github.com/stevenlovegrove/Pangolin) ```bash sudo apt-get install -y cmake-qt-gui git build-essential libusb-1.0-0-dev libudev-dev openjdk-7-jdk freeglut3-dev libglew-dev cuda-7-5 libsuitesparse-dev libeigen3-dev zlib1g-dev libjpeg-dev ``` Afterwards install [OpenNI2](https://github.com/occipital/OpenNI2) and [Pangolin](https://github.com/stevenlovegrove/Pangolin) from source. Note, you may need to manually tell CMake where OpenNI2 is since Occipital's fork does not have an install option. It is important to build Pangolin last so that it can find some of the libraries it has optional dependencies on. OpenNI2: ```bash cd ~/catkin_ws/src/Object-RPE/obj_pose_est/mapping mkdir deps cd deps git clone https://github.com/occipital/OpenNI2.git cd OpenNI2 make -j8 ``` Pangolin: ```bash cd ~/catkin_ws/src/Object-RPE/obj_pose_est/mapping/deps git clone https://github.com/stevenlovegrove/Pangolin.git cd Pangolin mkdir build cd build cmake ../ -DAVFORMAT_INCLUDE_DIR="" -DCPP11_NO_BOOST=ON make -j8 cd ../.. ``` Pangolin must be installed AFTER all the other libraries to make use of optional dependencies. When you have all of the dependencies installed, build the Core followed by the app. ## 2. Build core and app Build core: ```bash cd Core/ mkdir build cd build cmake ../src make -j8 ``` Build mapping app: ```bash cd app/ mkdir build cd build/ cmake ../src make -j8 ``` ================================================ FILE: obj_pose_est/mapping/app/note ================================================ mkdir build cd build/ cmake ../src make -j8 ./mapping -l /home/aass/catkin_ws/src/Object-RPE/data/ ================================================ FILE: obj_pose_est/mapping/app/src/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 2.6.0) project(mapping) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_SOURCE_DIR}") if(WIN32) macro(CANONIFY_BOOL var) if(${var}) set(${var} TRUE) else() set(${var} FALSE) endif() endmacro() endif() if(WIN32) find_package(JPEG REQUIRED) endif() find_package(LAPACK REQUIRED) find_package(BLAS REQUIRED) find_package(ZLIB REQUIRED) find_package(Pangolin 0.1 REQUIRED) find_package(CUDA REQUIRED) find_package(OpenNI2 REQUIRED) find_package(efusion REQUIRED) find_package(SuiteSparse REQUIRED) find_package(OpenCV 3.1 REQUIRED ) if(WIN32) find_package(RealSense QUIET) CANONIFY_BOOL(REALSENSE_FOUND) message(STATUS "librealsense found: ${REALSENSE_FOUND}") option(WITH_REALSENSE "Build with Intel RealSense support?" ${REALSENSE_FOUND}) endif() if(WIN32) include_directories(${JPEG_INCLUDE_DIR}) endif() include_directories(${ZLIB_INCLUDE_DIR}) include_directories(${EIGEN_INCLUDE_DIRS}) include_directories(${Pangolin_INCLUDE_DIRS}) include_directories(${CUDA_INCLUDE_DIRS}) include_directories(${EFUSION_INCLUDE_DIR}) include_directories(${OPENNI2_INCLUDE_DIR}) include_directories(${OpenCV_INCLUDE_DIRS}) if(WITH_REALSENSE) include_directories(${REALSENSE_INCLUDE_DIR}) add_definitions(-DWITH_REALSENSE) set(EXTRA_LIBS ${EXTRA_LIBS} ${REALSENSE_LIBRARY}) endif() file(GLOB srcs *.cpp) file(GLOB tools_srcs Tools/*.cpp) if(WIN32) file(GLOB hdrs *.h) file(GLOB tools_hdrs Tools/*.h) endif() if(WIN32) add_definitions(-Dlinux=0) add_definitions(-DWIN32_LEAN_AND_MEAN) add_definitions(-DNOMINMAX) set(ADDITIONAL_CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS}) set(EXTRA_WINDOWS_LIBS ${EXTRA_WINDOWS_LIBS} ws2_32 ${JPEG_LIBRARY}) else() add_definitions(-Dlinux=1) endif() set(CMAKE_CXX_FLAGS ${ADDITIONAL_CMAKE_CXX_FLAGS} "-O3 -msse2 -msse3 -Wall -std=c++11") #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -Wall -std=c++11") add_executable(mapping ${srcs} ${tools_srcs} ${hdrs} ${tools_hdrs} ) target_link_libraries(mapping ${EXTRA_WINDOWS_LIBS} ${ZLIB_LIBRARY} ${Pangolin_LIBRARIES} ${CUDA_LIBRARIES} ${EXTRA_LIBS} ${EFUSION_LIBRARY} ${OPENNI2_LIBRARY} ${SUITESPARSE_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES} ${OpenCV_LIBRARIES} ) INSTALL(TARGETS mapping RUNTIME DESTINATION bin LIBRARY DESTINATION lib ARCHIVE DESTINATION lib ) ================================================ FILE: obj_pose_est/mapping/app/src/FindBLAS.cmake ================================================ # Find BLAS library # # This module finds an installed library that implements the BLAS # linear-algebra interface (see http://www.netlib.org/blas/). # The list of libraries searched for is mainly taken # from the autoconf macro file, acx_blas.m4 (distributed at # http://ac-archive.sourceforge.net/ac-archive/acx_blas.html). # # This module sets the following variables: # BLAS_FOUND - set to true if a library implementing the BLAS interface # is found # BLAS_INCLUDE_DIR - Directories containing the BLAS header files # BLAS_DEFINITIONS - Compilation options to use BLAS # BLAS_LINKER_FLAGS - Linker flags to use BLAS (excluding -l # and -L). # BLAS_LIBRARIES_DIR - Directories containing the BLAS libraries. # May be null if BLAS_LIBRARIES contains libraries name using full path. # BLAS_LIBRARIES - List of libraries to link against BLAS interface. # May be null if the compiler supports auto-link (e.g. VC++). # BLAS_USE_FILE - The name of the cmake module to include to compile # applications or libraries using BLAS. # # The following variables control the behaviour of this module: # # BLAS_DIR: Specify a custom directory where suitesparse is located # libraries and headers will be searched for in # ${BLAS_DIR}/include and ${BLAS_DIR}/lib # # This module was modified by CGAL team: # - find BLAS library shipped with TAUCS # - find libraries for a C++ compiler, instead of Fortran # - added BLAS_INCLUDE_DIR, BLAS_DEFINITIONS and BLAS_LIBRARIES_DIR # - removed BLAS95_LIBRARIES # # TODO (CGAL): # - find CBLAS (http://www.netlib.org/cblas) on Unix? include(CheckFunctionExists) # This macro checks for the existence of the combination of fortran libraries # given by _list. If the combination is found, this macro checks (using the # check_function_exists macro) whether can link against that library # combination using the name of a routine given by _name using the linker # flags given by _flags. If the combination of libraries is found and passes # the link test, LIBRARIES is set to the list of complete library paths that # have been found and DEFINITIONS to the required definitions. # Otherwise, LIBRARIES is set to FALSE. # N.B. _prefix is the prefix applied to the names of all cached variables that # are generated internally and marked advanced by this macro. macro(check_fortran_libraries DEFINITIONS LIBRARIES _prefix _name _flags _list _path) #message("DEBUG: check_fortran_libraries(${_list} in ${_path})") # Check for the existence of the libraries given by _list set(_libraries_found TRUE) set(_libraries_work FALSE) set(${DEFINITIONS} "") set(${LIBRARIES} "") set(_combined_name) foreach(_library ${_list}) set(_combined_name ${_combined_name}_${_library}) if(_libraries_found) # search first in ${_path} find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${_path} NO_DEFAULT_PATH ) # if not found, search in environment variables and system if ( WIN32 ) find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${BLAS_DIR}/lib ${BLAS_DIR} ENV LIB ) elseif ( APPLE ) find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${BLAS_DIR}/lib /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH ) else () find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${BLAS_DIR}/lib ~/.linuxbrew/lib /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV LD_LIBRARY_PATH ) endif() #message("DEBUG: find_library(${_library}) = ${${_prefix}_${_library}_LIBRARY}") mark_as_advanced(${_prefix}_${_library}_LIBRARY) set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY}) set(_libraries_found ${${_prefix}_${_library}_LIBRARY}) endif(_libraries_found) endforeach(_library ${_list}) if(_libraries_found) set(_libraries_found ${${LIBRARIES}}) endif() # Test this combination of libraries with the Fortran/f2c interface. # We test the Fortran interface first as it is well standardized. if(_libraries_found AND NOT _libraries_work) set(${DEFINITIONS} "-D${_prefix}_USE_F2C") set(${LIBRARIES} ${_libraries_found}) # Some C++ linkers require the f2c library to link with Fortran libraries. # I do not know which ones, thus I just add the f2c library if it is available. find_package( F2C QUIET ) if ( F2C_FOUND ) set(${DEFINITIONS} ${${DEFINITIONS}} ${F2C_DEFINITIONS}) set(${LIBRARIES} ${${LIBRARIES}} ${F2C_LIBRARIES}) endif() set(CMAKE_REQUIRED_DEFINITIONS ${${DEFINITIONS}}) set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}}) #message("DEBUG: CMAKE_REQUIRED_DEFINITIONS = ${CMAKE_REQUIRED_DEFINITIONS}") #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") # Check if function exists with f2c calling convention (ie a trailing underscore) check_function_exists(${_name}_ ${_prefix}_${_name}_${_combined_name}_f2c_WORKS) #message("DEBUG: check_function_exists(${_name}_) = ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS}") set(CMAKE_REQUIRED_DEFINITIONS} "") set(CMAKE_REQUIRED_LIBRARIES "") mark_as_advanced(${_prefix}_${_name}_${_combined_name}_f2c_WORKS) set(_libraries_work ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS}) endif(_libraries_found AND NOT _libraries_work) # If not found, test this combination of libraries with a C interface. # A few implementations (ie ACML) provide a C interface. Unfortunately, there is no standard. if(_libraries_found AND NOT _libraries_work) set(${DEFINITIONS} "") set(${LIBRARIES} ${_libraries_found}) set(CMAKE_REQUIRED_DEFINITIONS "") set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}}) #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") check_function_exists(${_name} ${_prefix}_${_name}${_combined_name}_WORKS) #message("DEBUG: check_function_exists(${_name}) = ${${_prefix}_${_name}${_combined_name}_WORKS}") set(CMAKE_REQUIRED_LIBRARIES "") mark_as_advanced(${_prefix}_${_name}${_combined_name}_WORKS) set(_libraries_work ${${_prefix}_${_name}${_combined_name}_WORKS}) endif(_libraries_found AND NOT _libraries_work) # on failure if(NOT _libraries_work) set(${DEFINITIONS} "") set(${LIBRARIES} FALSE) endif() #message("DEBUG: ${DEFINITIONS} = ${${DEFINITIONS}}") #message("DEBUG: ${LIBRARIES} = ${${LIBRARIES}}") endmacro(check_fortran_libraries) # # main # # Is it already configured? if (BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) set(BLAS_FOUND TRUE) else() # reset variables set( BLAS_INCLUDE_DIR "" ) set( BLAS_DEFINITIONS "" ) set( BLAS_LINKER_FLAGS "" ) set( BLAS_LIBRARIES "" ) set( BLAS_LIBRARIES_DIR "" ) # Look first for the TAUCS library distributed with CGAL in auxiliary/taucs. # Set CGAL_TAUCS_FOUND, CGAL_TAUCS_INCLUDE_DIR and CGAL_TAUCS_LIBRARIES_DIR. #include(CGAL_Locate_CGAL_TAUCS) # Search for BLAS in CGAL_TAUCS_INCLUDE_DIR/CGAL_TAUCS_LIBRARIES_DIR (TAUCS shipped with CGAL)... if(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) # if VC++: done set( BLAS_INCLUDE_DIR "${CGAL_TAUCS_INCLUDE_DIR}" ) set( BLAS_LIBRARIES_DIR "${CGAL_TAUCS_LIBRARIES_DIR}" ) # ...else search for BLAS in $BLAS_LIB_DIR environment variable else(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) # # Search for BLAS in possible libraries # in $BLAS_LIB_DIR environment variable and in usual places. # # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS cblas_dgemm "" "cblas;f77blas;atlas" "${BLAS_LIB_DIR}" ) endif() # BLAS in PhiPACK libraries? (requires generic BLAS lib, too) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "sgemm;dgemm;blas" "${BLAS_LIB_DIR}" ) endif() # BLAS in Alpha CXML library? if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "cxml" "${BLAS_LIB_DIR}" ) endif() # BLAS in Alpha DXML library? (now called CXML, see above) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "dxml" "${BLAS_LIB_DIR}" ) endif() # BLAS in Sun Performance library? if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "-xlic_lib=sunperf" "sunperf;sunmath" "${BLAS_LIB_DIR}" ) if(BLAS_LIBRARIES) # Extra linker flag set(BLAS_LINKER_FLAGS "-xlic_lib=sunperf") endif() endif() # BLAS in SCSL library? (SGI/Cray Scientific Library) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "scsl" "${BLAS_LIB_DIR}" ) endif() # BLAS in SGIMATH library? if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "complib.sgimath" "${BLAS_LIB_DIR}" ) endif() # BLAS in IBM ESSL library? (requires generic BLAS lib, too) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "essl;blas" "${BLAS_LIB_DIR}" ) endif() # intel mkl 10 library? # TODO: add shared variants if (WIN32) # intel mkl library? (static, 32bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS SGEMM "" "mkl_intel_c;mkl_intel_thread;mkl_core;libiomp5md" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() # intel mkl library? (static, ia64 and em64t 64 bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS SGEMM "" "mkl_intel_lp64;mkl_intel_thread_lp64;mkl_core;libiomp5md" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() else(WIN32) # intel mkl library? (static, 32bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl_intel;mkl_intel_thread;mkl_core;iomp5;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() # intel mkl library? (static, ia64 and em64t 64 bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl_intel_lp64;mkl_intel_thread_lp64;mkl_core;iomp5;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() endif (WIN32) # older versions of intel mkl libs # intel mkl library? (shared) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl;guide;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() # intel mkl library? (static, 32bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl_ia32;guide;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() # intel mkl library? (static, ia64 64bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl_ipf;guide;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() # intel mkl library? (static, em64t 64bit) if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "mkl_em64t;guide;pthread" "${MKL_LIB_DIR} ${BLAS_LIB_DIR}" ) endif() #BLAS in acml library? if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "acml" "${BLAS_LIB_DIR}" ) endif() # Apple BLAS library? if(NOT BLAS_LIBRARIES) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "Accelerate" "${BLAS_LIB_DIR}" ) endif() if ( NOT BLAS_LIBRARIES ) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "vecLib" "${BLAS_LIB_DIR}" ) endif ( NOT BLAS_LIBRARIES ) # Generic BLAS library? # This configuration *must* be the last try as this library is notably slow. if ( NOT BLAS_LIBRARIES ) check_fortran_libraries( BLAS_DEFINITIONS BLAS_LIBRARIES BLAS sgemm "" "blas" "${BLAS_LIB_DIR}" ) endif() endif(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) if(BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) set(BLAS_FOUND TRUE) else() find_package(OpenBLAS) if(OpenBLAS_FOUND) set(BLAS_FOUND TRUE) set(BLAS_INCLUDE_DIR ${OpenBLAS_INCLUDE_DIRS}) set(BLAS_LIBRARIES ${OpenBLAS_LIBRARIES}) else() set(BLAS_FOUND FALSE) endif() endif() if(NOT BLAS_FIND_QUIETLY) if(BLAS_FOUND) message(STATUS "A library with BLAS API found.") else(BLAS_FOUND) if(BLAS_FIND_REQUIRED) message(FATAL_ERROR "A required library with BLAS API not found. Please specify library location.") else() message(STATUS "A library with BLAS API not found. Please specify library location.") endif() endif(BLAS_FOUND) endif(NOT BLAS_FIND_QUIETLY) # Add variables to cache set( BLAS_INCLUDE_DIR "${BLAS_INCLUDE_DIR}" CACHE PATH "Directories containing the BLAS header files" FORCE ) set( BLAS_DEFINITIONS "${BLAS_DEFINITIONS}" CACHE STRING "Compilation options to use BLAS" FORCE ) set( BLAS_LINKER_FLAGS "${BLAS_LINKER_FLAGS}" CACHE STRING "Linker flags to use BLAS" FORCE ) set( BLAS_LIBRARIES "${BLAS_LIBRARIES}" CACHE FILEPATH "BLAS libraries name" FORCE ) set( BLAS_LIBRARIES_DIR "${BLAS_LIBRARIES_DIR}" CACHE PATH "Directories containing the BLAS libraries" FORCE ) #message("DEBUG: BLAS_INCLUDE_DIR = ${BLAS_INCLUDE_DIR}") #message("DEBUG: BLAS_DEFINITIONS = ${BLAS_DEFINITIONS}") #message("DEBUG: BLAS_LINKER_FLAGS = ${BLAS_LINKER_FLAGS}") #message("DEBUG: BLAS_LIBRARIES = ${BLAS_LIBRARIES}") #message("DEBUG: BLAS_LIBRARIES_DIR = ${BLAS_LIBRARIES_DIR}") #message("DEBUG: BLAS_FOUND = ${BLAS_FOUND}") endif(BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) if(BLAS_FOUND) set(BLAS_FOUND ${BLAS_FOUND} CACHE INTERNAL "") set(BLAS_USE_FILE "CGAL_UseBLAS") endif(BLAS_FOUND) ================================================ FILE: obj_pose_est/mapping/app/src/FindLAPACK.cmake ================================================ # Find LAPACK library # # This module finds an installed library that implements the LAPACK # linear-algebra interface (see http://www.netlib.org/lapack/). # The approach follows mostly that taken for the autoconf macro file, acx_lapack.m4 # (distributed at http://ac-archive.sourceforge.net/ac-archive/acx_lapack.html). # # This module sets the following variables: # LAPACK_FOUND - set to true if a library implementing the LAPACK interface # is found # LAPACK_INCLUDE_DIR - Directories containing the LAPACK header files # LAPACK_DEFINITIONS - Compilation options to use LAPACK # LAPACK_LINKER_FLAGS - Linker flags to use LAPACK (excluding -l # and -L). # LAPACK_LIBRARIES_DIR - Directories containing the LAPACK libraries. # May be null if LAPACK_LIBRARIES contains libraries name using full path. # LAPACK_LIBRARIES - List of libraries to link against LAPACK interface. # May be null if the compiler supports auto-link (e.g. VC++). # LAPACK_USE_FILE - The name of the cmake module to include to compile # applications or libraries using LAPACK. # # This module was modified by CGAL team: # - find LAPACK library shipped with TAUCS # - find libraries for a C++ compiler, instead of Fortran # - added LAPACK_INCLUDE_DIR, LAPACK_DEFINITIONS and LAPACK_LIBRARIES_DIR # - removed LAPACK95_LIBRARIES # # TODO (CGAL): # - find CLAPACK (http://www.netlib.org/clapack) on Unix? include(CheckFunctionExists) include(CheckFortranFunctionExists) # This macro checks for the existence of the combination of fortran libraries # given by _list. If the combination is found, this macro checks (using the # check_function_exists macro) whether can link against that library # combination using the name of a routine given by _name using the linker # flags given by _flags. If the combination of libraries is found and passes # the link test, LIBRARIES is set to the list of complete library paths that # have been found and DEFINITIONS to the required definitions. # Otherwise, LIBRARIES is set to FALSE. # N.B. _prefix is the prefix applied to the names of all cached variables that # are generated internally and marked advanced by this macro. macro(check_lapack_libraries DEFINITIONS LIBRARIES _prefix _name _flags _list _blas _path) #message("DEBUG: check_lapack_libraries(${_list} in ${_path} with ${_blas})") # Check for the existence of the libraries given by _list set(_libraries_found TRUE) set(_libraries_work TRUE) set(${DEFINITIONS} "") set(${LIBRARIES} "") set(_combined_name) foreach(_library ${_list}) set(_combined_name ${_combined_name}_${_library}) if(_libraries_found) # search first in ${_path} find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${LAPACK_DIR} ${LAPACK_DIR}/lib ${_path} NO_DEFAULT_PATH ) # if not found, search in environment variables and system if ( WIN32 ) find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${LAPACK_DIR} ${LAPACK_DIR}/lib ENV LIB ) elseif ( APPLE ) find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${LAPACK_DIR} ${LAPACK_DIR}/lib /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH ) else () find_library(${_prefix}_${_library}_LIBRARY NAMES ${_library} PATHS ${LAPACK_DIR} ${LAPACK_DIR}/lib ~/.linuxbrew/lib /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV LD_LIBRARY_PATH ) endif() mark_as_advanced(${_prefix}_${_library}_LIBRARY) set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY}) set(_libraries_found ${${_prefix}_${_library}_LIBRARY}) endif(_libraries_found) endforeach(_library ${_list}) if(_libraries_found) set(_libraries_found ${${LIBRARIES}}) endif() # Test this combination of libraries with the Fortran/f2c interface. # We test the Fortran interface first as it is well standardized. if(_libraries_found AND NOT _libraries_work) set(${DEFINITIONS} "-D${_prefix}_USE_F2C") set(${LIBRARIES} ${_libraries_found}) # Some C++ linkers require the f2c library to link with Fortran libraries. # I do not know which ones, thus I just add the f2c library if it is available. find_package( F2C QUIET ) if ( F2C_FOUND ) set(${DEFINITIONS} ${${DEFINITIONS}} ${F2C_DEFINITIONS}) set(${LIBRARIES} ${${LIBRARIES}} ${F2C_LIBRARIES}) endif() set(CMAKE_REQUIRED_DEFINITIONS ${${DEFINITIONS}}) set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}} ${_blas}) #message("DEBUG: CMAKE_REQUIRED_DEFINITIONS = ${CMAKE_REQUIRED_DEFINITIONS}") #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") # Check if function exists with f2c calling convention (ie a trailing underscore) check_function_exists(${_name}_ ${_prefix}_${_name}_${_combined_name}_f2c_WORKS) set(CMAKE_REQUIRED_DEFINITIONS} "") set(CMAKE_REQUIRED_LIBRARIES "") mark_as_advanced(${_prefix}_${_name}_${_combined_name}_f2c_WORKS) set(_libraries_work ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS}) endif(_libraries_found AND NOT _libraries_work) # If not found, test this combination of libraries with a C interface. # A few implementations (ie ACML) provide a C interface. Unfortunately, there is no standard. if(_libraries_found AND NOT _libraries_work) set(${DEFINITIONS} "") set(${LIBRARIES} ${_libraries_found}) set(CMAKE_REQUIRED_DEFINITIONS "") set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}} ${_blas}) #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") check_function_exists(${_name} ${_prefix}_${_name}${_combined_name}_WORKS) set(CMAKE_REQUIRED_LIBRARIES "") mark_as_advanced(${_prefix}_${_name}${_combined_name}_WORKS) set(_libraries_work ${${_prefix}_${_name}${_combined_name}_WORKS}) endif(_libraries_found AND NOT _libraries_work) # on failure if(NOT _libraries_work) set(${DEFINITIONS} "") set(${LIBRARIES} FALSE) endif() #message("DEBUG: ${DEFINITIONS} = ${${DEFINITIONS}}") #message("DEBUG: ${LIBRARIES} = ${${LIBRARIES}}") endmacro(check_lapack_libraries) # # main # # LAPACK requires BLAS if(LAPACK_FIND_QUIETLY OR NOT LAPACK_FIND_REQUIRED) find_package(BLAS) else() find_package(BLAS REQUIRED) endif() if (NOT BLAS_FOUND) message(STATUS "LAPACK requires BLAS.") set(LAPACK_FOUND FALSE) # Is it already configured? elseif (LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES) set(LAPACK_FOUND TRUE) else() # reset variables set( LAPACK_INCLUDE_DIR "" ) set( LAPACK_DEFINITIONS "" ) set( LAPACK_LINKER_FLAGS "" ) # unused (yet) set( LAPACK_LIBRARIES "" ) set( LAPACK_LIBRARIES_DIR "" ) # Look first for the TAUCS library distributed with CGAL in auxiliary/taucs. # Set CGAL_TAUCS_FOUND, CGAL_TAUCS_INCLUDE_DIR and CGAL_TAUCS_LIBRARIES_DIR. #include(CGAL_Locate_CGAL_TAUCS) # Search for LAPACK in CGAL_TAUCS_INCLUDE_DIR/CGAL_TAUCS_LIBRARIES_DIR (TAUCS shipped with CGAL), # else in $LAPACK_INC_DIR/$LAPACK_LIB_DIR environment variables. if(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) # if VC++: done set( LAPACK_INCLUDE_DIR "${CGAL_TAUCS_INCLUDE_DIR}" ) set( LAPACK_LIBRARIES_DIR "${CGAL_TAUCS_LIBRARIES_DIR}" ) else(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) # # If Unix, search for LAPACK function in possible libraries # #intel mkl lapack? if(NOT LAPACK_LIBRARIES) check_lapack_libraries( LAPACK_DEFINITIONS LAPACK_LIBRARIES LAPACK cheev "" "mkl_lapack" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif() #acml lapack? if(NOT LAPACK_LIBRARIES) check_lapack_libraries( LAPACK_DEFINITIONS LAPACK_LIBRARIES LAPACK cheev "" "acml" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif() # Apple LAPACK library? if(NOT LAPACK_LIBRARIES) check_lapack_libraries( LAPACK_DEFINITIONS LAPACK_LIBRARIES LAPACK cheev "" "Accelerate" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif() if ( NOT LAPACK_LIBRARIES ) check_lapack_libraries( LAPACK_DEFINITIONS LAPACK_LIBRARIES LAPACK cheev "" "vecLib" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif ( NOT LAPACK_LIBRARIES ) # Generic LAPACK library? # This configuration *must* be the last try as this library is notably slow. if ( NOT LAPACK_LIBRARIES ) check_lapack_libraries( LAPACK_DEFINITIONS LAPACK_LIBRARIES LAPACK cheev "" "lapack" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif() check_lapack_libraries( LAPACKE_DEFINITIONS LAPACKE_LIBRARIES LAPACK cheev "" "lapacke" "${BLAS_LIBRARIES}" "${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR" ) endif(CGAL_TAUCS_FOUND AND CGAL_AUTO_LINK_ENABLED) if(LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES) set(LAPACK_FOUND TRUE) else() find_package(OpenBLAS) if(OpenBLAS_FOUND) set(LAPACK_FOUND TRUE) set(LAPACK_INCLUDE_DIR ${OpenBLAS_INCLUDE_DIRS}) set(LAPACK_LIBRARIES ${OpenBLAS_LIBRARIES}) else() set(LAPACK_FOUND FALSE) endif() endif() if(NOT LAPACK_FIND_QUIETLY) if(LAPACK_FOUND) message(STATUS "A library with LAPACK API found.") else(LAPACK_FOUND) if(LAPACK_FIND_REQUIRED) message(FATAL_ERROR "A required library with LAPACK API not found. Please specify library location.") else() message(STATUS "A library with LAPACK API not found. Please specify library location.") endif() endif(LAPACK_FOUND) endif(NOT LAPACK_FIND_QUIETLY) # Add variables to cache set( LAPACK_INCLUDE_DIR "${LAPACK_INCLUDE_DIR}" CACHE PATH "Directories containing the LAPACK header files" FORCE ) set( LAPACK_DEFINITIONS "${LAPACK_DEFINITIONS}" CACHE STRING "Compilation options to use LAPACK" FORCE ) set( LAPACK_LINKER_FLAGS "${LAPACK_LINKER_FLAGS}" CACHE STRING "Linker flags to use LAPACK" FORCE ) set( LAPACK_LIBRARIES "${LAPACK_LIBRARIES}" CACHE FILEPATH "LAPACK libraries name" FORCE ) set( LAPACK_LIBRARIES_DIR "${LAPACK_LIBRARIES_DIR}" CACHE PATH "Directories containing the LAPACK libraries" FORCE ) #message("DEBUG: LAPACK_INCLUDE_DIR = ${LAPACK_INCLUDE_DIR}") #message("DEBUG: LAPACK_DEFINITIONS = ${LAPACK_DEFINITIONS}") #message("DEBUG: LAPACK_LINKER_FLAGS = ${LAPACK_LINKER_FLAGS}") #message("DEBUG: LAPACK_LIBRARIES = ${LAPACK_LIBRARIES}") #message("DEBUG: LAPACK_LIBRARIES_DIR = ${LAPACK_LIBRARIES_DIR}") #message("DEBUG: LAPACK_FOUND = ${LAPACK_FOUND}") endif(NOT BLAS_FOUND) if(LAPACK_FOUND) set(LAPACK_FOUND ${LAPACK_FOUND} CACHE INTERNAL "") set(LAPACK_USE_FILE "CGAL_UseLAPACK") endif(LAPACK_FOUND) ================================================ FILE: obj_pose_est/mapping/app/src/FindOpenNI2.cmake ================================================ ############################################################################### # Find OpenNI2 # # This sets the following variables: # OPENNI2_FOUND - True if OPENNI was found. # OPENNI2_INCLUDE_DIRS - Directories containing the OPENNI include files. # OPENNI2_LIBRARIES - Libraries needed to use OPENNI. find_package(PkgConfig) if(${CMAKE_VERSION} VERSION_LESS 2.8.2) pkg_check_modules(PC_OPENNI openni2-dev) else() pkg_check_modules(PC_OPENNI QUIET openni2-dev) endif() set(OPENNI2_DEFINITIONS ${PC_OPENNI_CFLAGS_OTHER}) #add a hint so that it can find it without the pkg-config find_path(OPENNI2_INCLUDE_DIR OpenNI.h HINTS ${PC_OPENNI_INCLUDEDIR} ${PC_OPENNI_INCLUDE_DIRS} PATHS "${PROGRAM_FILES}/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../../OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../code/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../../code/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../deps/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../deps/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../deps/OpenNI2/Include" "${CMAKE_SOURCE_DIR}/../../../../deps/OpenNI2/Include" /usr/include /user/include PATH_SUFFIXES openni2 ni2 ) if(${CMAKE_CL_64}) set(OPENNI_PATH_SUFFIXES lib64) else() set(OPENNI_PATH_SUFFIXES lib) endif() #add a hint so that it can find it without the pkg-config find_library(OPENNI2_LIBRARY NAMES OpenNI2 HINTS ${PC_OPENNI_LIBDIR} ${PC_OPENNI_LIBRARY_DIRS} PATHS "${PROGRAM_FILES}}/OpenNI2/Redist" "${PROGRAM_FILES}/OpenNI2" "${CMAKE_SOURCE_DIR}/../OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../../OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../code/OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../../code/OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../deps/OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../deps/OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../deps/OpenNI2/Bin/x64-Release" "${CMAKE_SOURCE_DIR}/../../../../deps/OpenNI2/Bin/x64-Release" /usr/lib /user/lib PATH_SUFFIXES ${OPENNI_PATH_SUFFIXES} ) set(OPENNI2_INCLUDE_DIRS ${OPENNI2_INCLUDE_DIR}) set(OPENNI2_LIBRARIES ${OPENNI2_LIBRARY}) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(OpenNI2 DEFAULT_MSG OPENNI2_LIBRARY OPENNI2_INCLUDE_DIR) mark_as_advanced(OPENNI2_LIBRARY OPENNI2_INCLUDE_DIR) ================================================ FILE: obj_pose_est/mapping/app/src/FindRealSense.cmake ================================================ set(REALSENSE_ROOT "/usr/local" CACHE PATH "Root directory of libREALSENSE") FIND_PATH(REALSENSE_INCLUDE_DIR libREALSENSE HINTS "${REALSENSE_ROOT}/include") FIND_LIBRARY(REALSENSE_LIBRARY REALSENSE HINTS "${REALSENSE_ROOT}/bin/x64" "${REALSENSE_ROOT}/lib") find_package_handle_standard_args(REALSENSE DEFAULT_MSG REALSENSE_LIBRARY REALSENSE_INCLUDE_DIR) mark_as_advanced(REALSENSE_LIBRARY REALSENSE_INCLUDE_DIR) ================================================ FILE: obj_pose_est/mapping/app/src/FindSuiteSparse.cmake ================================================ # - Try to find SUITESPARSE # Once done this will define # # SUITESPARSE_FOUND - system has SUITESPARSE # SUITESPARSE_INCLUDE_DIRS - the SUITESPARSE include directory # SUITESPARSE_LIBRARIES - Link these to use SUITESPARSE # SUITESPARSE_SPQR_LIBRARY - name of spqr library (necessary due to error in debian package) # SUITESPARSE_SPQR_LIBRARY_DIR - name of spqr library (necessary due to error in debian package) # SUITESPARSE_LIBRARY_DIR - Library main directory containing suitesparse libs # SUITESPARSE_LIBRARY_DIRS - all Library directories containing suitesparse libs # SUITESPARSE_SPQR_VALID - automatic identification whether or not spqr package is installed correctly IF (SUITESPARSE_INCLUDE_DIRS) # Already in cache, be silent SET(SUITESPARSE_FIND_QUIETLY TRUE) ENDIF (SUITESPARSE_INCLUDE_DIRS) if (WIN32) # the libraries may have lib prefix set(ORIGINAL_CMAKE_FIND_LIBRARY_PREFIXES "${CMAKE_FIND_LIBRARY_PREFIXES}") set(CMAKE_FIND_LIBRARY_PREFIXES "lib" "" "${CMAKE_FIND_LIBRARY_PREFIXES}") endif () FIND_PATH( SUITESPARSE_INCLUDE_DIR cholmod.h PATHS /usr/local/include /usr/include /usr/include/suitesparse/ ${CMAKE_SOURCE_DIR}/MacOS/Libs/cholmod PATH_SUFFIXES cholmod/ CHOLMOD/ ) FIND_PATH( SUITESPARSE_LIBRARY_DIR NAMES libcholmod.so libcholmod.a PATHS /usr/lib /usr/lib64 /usr/lib/x86_64-linux-gnu /usr/lib/i386-linux-gnu /usr/local/lib ) # Add cholmod include directory to collection include directories IF ( SUITESPARSE_INCLUDE_DIR ) list ( APPEND SUITESPARSE_INCLUDE_DIRS ${SUITESPARSE_INCLUDE_DIR} ) ENDIF( SUITESPARSE_INCLUDE_DIR ) # if we found the library, add it to the defined libraries IF ( SUITESPARSE_LIBRARY_DIR ) FIND_LIBRARY( SUITESPARSE_AMD_LIBRARY NAMES amd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CAMD_LIBRARY NAMES camd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CCOLAMD_LIBRARY NAMES ccolamd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CHOLMOD_LIBRARY NAMES cholmod PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_COLAMD_LIBRARY NAMES colamd PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_CXSPARSE_LIBRARY NAMES cxsparse PATHS ${SUITESPARSE_LIBRARY_DIR} ) FIND_LIBRARY( SUITESPARSE_SUITESPARSECONFIG_LIBRARY NAMES suitesparseconfig PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF ( WIN32 ) FIND_LIBRARY( SUITESPARSE_BLAS_LIBRARY NAMES blas PATHS ${SUITESPARSE_LIBRARY_DIR}/lapack_blas_windows ) FIND_LIBRARY( SUITESPARSE_LAPACK_LIBRARY NAMES lapack PATHS ${SUITESPARSE_LIBRARY_DIR}/lapack_blas_windows ) ENDIF () list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_AMD_LIBRARY} ${SUITESPARSE_CAMD_LIBRARY} ${SUITESPARSE_CCOLAMD_LIBRARY} ${SUITESPARSE_CHOLMOD_LIBRARY} ${SUITESPARSE_COLAMD_LIBRARY} ${SUITESPARSE_CXSPARSE_LIBRARY} ${SUITESPARSE_SUITESPARSECONFIG_LIBRARY} ${SUITESPARSE_BLAS_LIBRARY} ${SUITESPARSE_LAPACK_LIBRARY}) # Metis and spqr are optional FIND_LIBRARY( SUITESPARSE_METIS_LIBRARY NAMES metis PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF (SUITESPARSE_METIS_LIBRARY) list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_METIS_LIBRARY}) ENDIF(SUITESPARSE_METIS_LIBRARY) if(EXISTS "${SUITESPARSE_INCLUDE_DIR}/SuiteSparseQR.hpp") SET(SUITESPARSE_SPQR_VALID TRUE CACHE BOOL "SuiteSparseSPQR valid") else() SET(SUITESPARSE_SPQR_VALID false CACHE BOOL "SuiteSparseSPQR valid") endif() if(SUITESPARSE_SPQR_VALID) FIND_LIBRARY( SUITESPARSE_SPQR_LIBRARY NAMES spqr PATHS ${SUITESPARSE_LIBRARY_DIR} ) IF (SUITESPARSE_SPQR_LIBRARY) list ( APPEND SUITESPARSE_LIBRARIES ${SUITESPARSE_SPQR_LIBRARY}) ENDIF (SUITESPARSE_SPQR_LIBRARY) endif() ENDIF( SUITESPARSE_LIBRARY_DIR ) IF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) SET(SUITESPARSE_FOUND TRUE) MESSAGE(STATUS "Found SuiteSparse") ELSE (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) SET( SUITESPARSE_FOUND FALSE ) MESSAGE(FATAL_ERROR "Unable to find SuiteSparse") ENDIF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) if (WIN32) set(CMAKE_FIND_LIBRARY_PREFIXES "${ORIGINAL_CMAKE_FIND_LIBRARY_PREFIXES}") endif () ================================================ FILE: obj_pose_est/mapping/app/src/Findefusion.cmake ================================================ ############################################################################### # Find efusion # # This sets the following variables: # EFUSION_FOUND - True if EFUSION was found. # EFUSION_INCLUDE_DIRS - Directories containing the EFUSION include files. # EFUSION_LIBRARIES - Libraries needed to use EFUSION. find_path(EFUSION_INCLUDE_DIR ElasticFusion.h PATHS ${CMAKE_CURRENT_SOURCE_DIR}/../../Core/src PATH_SUFFIXES Core ) find_library(EFUSION_LIBRARY NAMES libefusion.so PATHS ${CMAKE_CURRENT_SOURCE_DIR}/../../Core/build ${CMAKE_CURRENT_SOURCE_DIR}/../../Core/src/build PATH_SUFFIXES ${EFUSION_PATH_SUFFIXES} ) set(EFUSION_INCLUDE_DIRS ${EFUSION_INCLUDE_DIR}) set(EFUSION_LIBRARIES ${EFUSION_LIBRARY}) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(EFUSION DEFAULT_MSG EFUSION_LIBRARY EFUSION_INCLUDE_DIR) if(NOT WIN32) mark_as_advanced(EFUSION_LIBRARY EFUSION_INCLUDE_DIR) endif() ================================================ FILE: obj_pose_est/mapping/app/src/Main.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "MainController.h" int main(int argc, char * argv[]) { MainController mainController(argc, argv); mainController.launch(); return 0; } ================================================ FILE: obj_pose_est/mapping/app/src/MainController.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "MainController.h" MainController::MainController(int argc, char * argv[]) : good(true), eFusion(0), gui(0), groundTruthOdometry(0), logReader(0), framesToSkip(0), img_count(0), img_num(100), resetButton(false), resizeStream(0) { Parse::get().arg(argc, argv, "-num_frames", img_num); std::string empty; iclnuim = Parse::get().arg(argc, argv, "-icl", empty) > -1; std::string calibrationFile; Parse::get().arg(argc, argv, "-cal", calibrationFile); Resolution::getInstance(640, 480); if(calibrationFile.length()) { loadCalibration(calibrationFile); } else { Intrinsics::getInstance(528, 528, 320, 240); } //Parse::get().arg(argc, argv, "-l", logFile); Parse::get().arg(argc, argv, "-l", data_dir); logFile = data_dir + "map.klg"; if(logFile.length()) { logReader = new RawLogReader(logFile, Parse::get().arg(argc, argv, "-f", empty) > -1); } else { bool flipColors = Parse::get().arg(argc,argv,"-f",empty) > -1; logReader = new LiveLogReader(logFile, flipColors, LiveLogReader::CameraType::OpenNI2); good = ((LiveLogReader *)logReader)->cam->ok(); #ifdef WITH_REALSENSE if(!good) { delete logReader; logReader = new LiveLogReader(logFile, flipColors, LiveLogReader::CameraType::RealSense); good = ((LiveLogReader *)logReader)->cam->ok(); } #endif } if(Parse::get().arg(argc, argv, "-p", poseFile) > 0) { groundTruthOdometry = new GroundTruthOdometry(poseFile); } confidence = 10.0f; depth = 3.0f; icp = 10.0f; icpErrThresh = 5e-05; covThresh = 1e-05; photoThresh = 115; fernThresh = 0.3095f; timeDelta = 200; icpCountThresh = 40000; start = 1; so3 = !(Parse::get().arg(argc, argv, "-nso", empty) > -1); end = std::numeric_limits::max(); //Funny bound, since we predict times in this format really! Parse::get().arg(argc, argv, "-c", confidence); Parse::get().arg(argc, argv, "-d", depth); Parse::get().arg(argc, argv, "-i", icp); Parse::get().arg(argc, argv, "-ie", icpErrThresh); Parse::get().arg(argc, argv, "-cv", covThresh); Parse::get().arg(argc, argv, "-pt", photoThresh); Parse::get().arg(argc, argv, "-ft", fernThresh); Parse::get().arg(argc, argv, "-t", timeDelta); Parse::get().arg(argc, argv, "-ic", icpCountThresh); Parse::get().arg(argc, argv, "-s", start); Parse::get().arg(argc, argv, "-e", end); logReader->flipColors = Parse::get().arg(argc, argv, "-f", empty) > -1; openLoop = !groundTruthOdometry && Parse::get().arg(argc, argv, "-o", empty) > -1; reloc = Parse::get().arg(argc, argv, "-rl", empty) > -1; frameskip = Parse::get().arg(argc, argv, "-fs", empty) > -1; quiet = Parse::get().arg(argc, argv, "-q", empty) > -1; fastOdom = Parse::get().arg(argc, argv, "-fo", empty) > -1; rewind = Parse::get().arg(argc, argv, "-r", empty) > -1; frameToFrameRGB = Parse::get().arg(argc, argv, "-ftf", empty) > -1; gui = new GUI(logFile.length() == 0, Parse::get().arg(argc, argv, "-sc", empty) > -1); gui->flipColors->Ref().Set(logReader->flipColors); gui->rgbOnly->Ref().Set(false); gui->pyramid->Ref().Set(true); gui->fastOdom->Ref().Set(fastOdom); gui->confidenceThreshold->Ref().Set(confidence); gui->depthCutoff->Ref().Set(depth); gui->icpWeight->Ref().Set(icp); gui->so3->Ref().Set(so3); gui->frameToFrameRGB->Ref().Set(frameToFrameRGB); resizeStream = new Resize(Resolution::getInstance().width(), Resolution::getInstance().height(), Resolution::getInstance().width() / 2, Resolution::getInstance().height() / 2); } MainController::~MainController() { if(eFusion) { delete eFusion; } if(gui) { delete gui; } if(groundTruthOdometry) { delete groundTruthOdometry; } if(logReader) { delete logReader; } if(resizeStream) { delete resizeStream; } } void MainController::loadCalibration(const std::string & filename) { std::ifstream file(filename); std::string line; assert(!file.eof()); double fx, fy, cx, cy; std::getline(file, line); int n = sscanf(line.c_str(), "%lg %lg %lg %lg", &fx, &fy, &cx, &cy); assert(n == 4 && "Ooops, your calibration file should contain a single line with fx fy cx cy!"); Intrinsics::getInstance(fx, fy, cx, cy); } void MainController::launch() { while(good) { if(eFusion) { run(); } if(eFusion == 0 || resetButton) { resetButton = false; img_count = 0; if(eFusion) { delete eFusion; } logReader->rewind(); eFusion = new ElasticFusion(openLoop ? std::numeric_limits::max() / 2 : timeDelta, icpCountThresh, icpErrThresh, covThresh, !openLoop, iclnuim, reloc, photoThresh, confidence, depth, icp, fastOdom, fernThresh, so3, frameToFrameRGB, logReader->getFile()); } else { break; } } } void MainController::run() { cv::Mat rgb_img, depth_img; while(!pangolin::ShouldQuit() && img_count <= img_num && !(eFusion->getTick() == end && quiet)) { img_count++; int index = 1000000 + img_count; std::string index_str = std::to_string(index); std::string rgb_dir = data_dir + "rgb/" + index_str.substr(1,6) + "-color.png"; std::string depth_dir = data_dir + "depth/" + index_str.substr(1,6) + "-depth.png"; rgb_img = cv::imread(rgb_dir, -1); depth_img = cv::imread(depth_dir, -1); if(!rgb_img.data || !depth_img.data) { if(img_count == img_num) { eFusion->saveFilename = data_dir + "map"; eFusion->savePly(); break; } continue; } cv::cvtColor(rgb_img, rgb_img, CV_BGR2RGB); if(!gui->pause->Get() || pangolin::Pushed(*gui->step)) { if(true/* (logReader->hasMore() || rewind) && eFusion->getTick() < end */) { TICK("LogRead"); /* if(rewind) { if(!logReader->hasMore()) { logReader->getBack(); } else { logReader->getNext(); } if(logReader->rewound()) { logReader->currentFrame = 0; } } else { logReader->getNext(); } */ TOCK("LogRead"); if(eFusion->getTick() < start) { eFusion->setTick(start); logReader->fastForward(start); } float weightMultiplier = framesToSkip + 1; if(framesToSkip > 0) { eFusion->setTick(eFusion->getTick() + framesToSkip); logReader->fastForward(logReader->currentFrame + framesToSkip); framesToSkip = 0; } Eigen::Matrix4f * currentPose = 0; if(groundTruthOdometry) { currentPose = new Eigen::Matrix4f; currentPose->setIdentity(); *currentPose = groundTruthOdometry->getTransformation(logReader->timestamp); } trajectory.push_back(eFusion->getCurrPose()); eFusion->processFrame(rgb_img.data, (unsigned short*)depth_img.data, img_count, currentPose, weightMultiplier); if(currentPose) { delete currentPose; } if(frameskip && Stopwatch::getInstance().getTimings().at("Run") > 1000.f / 30.f) { framesToSkip = int(Stopwatch::getInstance().getTimings().at("Run") / (1000.f / 30.f)); } } } else { eFusion->predict(); } TICK("GUI"); if(gui->followPose->Get()) { pangolin::OpenGlMatrix mv; Eigen::Matrix4f currPose = eFusion->getCurrPose(); Eigen::Matrix3f currRot = currPose.topLeftCorner(3, 3); Eigen::Quaternionf currQuat(currRot); Eigen::Vector3f forwardVector(0, 0, 1); Eigen::Vector3f upVector(0, iclnuim ? 1 : -1, 0); Eigen::Vector3f forward = (currQuat * forwardVector).normalized(); Eigen::Vector3f up = (currQuat * upVector).normalized(); Eigen::Vector3f eye(currPose(0, 3), currPose(1, 3), currPose(2, 3)); eye -= forward; Eigen::Vector3f at = eye + forward; Eigen::Vector3f z = (eye - at).normalized(); // Forward Eigen::Vector3f x = up.cross(z).normalized(); // Right Eigen::Vector3f y = z.cross(x); Eigen::Matrix4d m; m << x(0), x(1), x(2), -(x.dot(eye)), y(0), y(1), y(2), -(y.dot(eye)), z(0), z(1), z(2), -(z.dot(eye)), 0, 0, 0, 1; memcpy(&mv.m[0], m.data(), sizeof(Eigen::Matrix4d)); gui->s_cam.SetModelViewMatrix(mv); } gui->preCall(); std::stringstream stri; stri << eFusion->getModelToModel().lastICPCount; gui->trackInliers->Ref().Set(stri.str()); std::stringstream stre; stre << (std::isnan(eFusion->getModelToModel().lastICPError) ? 0 : eFusion->getModelToModel().lastICPError); gui->trackRes->Ref().Set(stre.str()); if(!gui->pause->Get()) { gui->resLog.Log((std::isnan(eFusion->getModelToModel().lastICPError) ? std::numeric_limits::max() : eFusion->getModelToModel().lastICPError), icpErrThresh); gui->inLog.Log(eFusion->getModelToModel().lastICPCount, icpCountThresh); } Eigen::Matrix4f pose = eFusion->getCurrPose(); if(gui->drawRawCloud->Get() || gui->drawFilteredCloud->Get()) { eFusion->computeFeedbackBuffers(); } if(gui->drawRawCloud->Get()) { eFusion->getFeedbackBuffers().at(FeedbackBuffer::RAW)->render(gui->s_cam.GetProjectionModelViewMatrix(), pose, gui->drawNormals->Get(), gui->drawColors->Get()); } if(gui->drawFilteredCloud->Get()) { eFusion->getFeedbackBuffers().at(FeedbackBuffer::FILTERED)->render(gui->s_cam.GetProjectionModelViewMatrix(), pose, gui->drawNormals->Get(), gui->drawColors->Get()); } if(gui->drawGlobalModel->Get()) { glFinish(); TICK("Global"); if(gui->drawFxaa->Get()) { gui->drawFXAA(gui->s_cam.GetProjectionModelViewMatrix(), gui->s_cam.GetModelViewMatrix(), eFusion->getGlobalModel().model(), eFusion->getConfidenceThreshold(), eFusion->getTick(), eFusion->getTimeDelta(), iclnuim); } else { eFusion->getGlobalModel().renderPointCloud(gui->s_cam.GetProjectionModelViewMatrix(), eFusion->getConfidenceThreshold(), gui->drawUnstable->Get(), gui->drawNormals->Get(), gui->drawColors->Get(), gui->drawPoints->Get(), gui->drawWindow->Get(), gui->drawTimes->Get(), eFusion->getTick(), eFusion->getTimeDelta()); } glFinish(); TOCK("Global"); } if(eFusion->getLost()) { glColor3f(1, 1, 0); } else { glColor3f(1, 0, 1); } gui->drawFrustum(pose); glColor3f(1, 1, 1); if(gui->drawFerns->Get()) { glColor3f(0, 0, 0); for(size_t i = 0; i < eFusion->getFerns().frames.size(); i++) { if((int)i == eFusion->getFerns().lastClosest) continue; gui->drawFrustum(eFusion->getFerns().frames.at(i)->pose); } glColor3f(1, 1, 1); } if(gui->drawDefGraph->Get()) { const std::vector & graph = eFusion->getLocalDeformation().getGraph(); for(size_t i = 0; i < graph.size(); i++) { pangolin::glDrawCross(graph.at(i)->position(0), graph.at(i)->position(1), graph.at(i)->position(2), 0.1); for(size_t j = 0; j < graph.at(i)->neighbours.size(); j++) { pangolin::glDrawLine(graph.at(i)->position(0), graph.at(i)->position(1), graph.at(i)->position(2), graph.at(graph.at(i)->neighbours.at(j))->position(0), graph.at(graph.at(i)->neighbours.at(j))->position(1), graph.at(graph.at(i)->neighbours.at(j))->position(2)); } } } if(eFusion->getFerns().lastClosest != -1) { glColor3f(1, 0, 0); gui->drawFrustum(eFusion->getFerns().frames.at(eFusion->getFerns().lastClosest)->pose); glColor3f(1, 1, 1); } const std::vector & poseMatches = eFusion->getPoseMatches(); int maxDiff = 0; for(size_t i = 0; i < poseMatches.size(); i++) { if(poseMatches.at(i).secondId - poseMatches.at(i).firstId > maxDiff) { maxDiff = poseMatches.at(i).secondId - poseMatches.at(i).firstId; } } for(size_t i = 0; i < poseMatches.size(); i++) { if(gui->drawDeforms->Get()) { if(poseMatches.at(i).fern) { glColor3f(1, 0, 0); } else { glColor3f(0, 1, 0); } for(size_t j = 0; j < poseMatches.at(i).constraints.size(); j++) { pangolin::glDrawLine(poseMatches.at(i).constraints.at(j).sourcePoint(0), poseMatches.at(i).constraints.at(j).sourcePoint(1), poseMatches.at(i).constraints.at(j).sourcePoint(2), poseMatches.at(i).constraints.at(j).targetPoint(0), poseMatches.at(i).constraints.at(j).targetPoint(1), poseMatches.at(i).constraints.at(j).targetPoint(2)); } } } glColor3f(1, 1, 1); eFusion->normaliseDepth(0.3f, gui->depthCutoff->Get()); for(std::map::const_iterator it = eFusion->getTextures().begin(); it != eFusion->getTextures().end(); ++it) { if(it->second->draw) { gui->displayImg(it->first, it->second); } } eFusion->getIndexMap().renderDepth(gui->depthCutoff->Get()); gui->displayImg("ModelImg", eFusion->getIndexMap().imageTex()); gui->displayImg("Model", eFusion->getIndexMap().drawTex()); std::stringstream strs; strs << eFusion->getGlobalModel().lastCount(); gui->totalPoints->operator=(strs.str()); std::stringstream strs2; strs2 << eFusion->getLocalDeformation().getGraph().size(); gui->totalNodes->operator=(strs2.str()); std::stringstream strs3; strs3 << eFusion->getFerns().frames.size(); gui->totalFerns->operator=(strs3.str()); std::stringstream strs4; strs4 << eFusion->getDeforms(); gui->totalDefs->operator=(strs4.str()); std::stringstream strs5; strs5 << eFusion->getTick() << "/" << img_num; gui->logProgress->operator=(strs5.str()); std::stringstream strs6; strs6 << eFusion->getFernDeforms(); gui->totalFernDefs->operator=(strs6.str()); gui->postCall(); logReader->flipColors = gui->flipColors->Get(); eFusion->setRgbOnly(gui->rgbOnly->Get()); eFusion->setPyramid(gui->pyramid->Get()); eFusion->setFastOdom(gui->fastOdom->Get()); eFusion->setConfidenceThreshold(gui->confidenceThreshold->Get()); eFusion->setDepthCutoff(gui->depthCutoff->Get()); eFusion->setIcpWeight(gui->icpWeight->Get()); eFusion->setSo3(gui->so3->Get()); eFusion->setFrameToFrameRGB(gui->frameToFrameRGB->Get()); resetButton = pangolin::Pushed(*gui->reset); if(gui->autoSettings) { static bool last = gui->autoSettings->Get(); if(gui->autoSettings->Get() != last) { last = gui->autoSettings->Get(); static_cast(logReader)->setAuto(last); } } Stopwatch::getInstance().sendAll(); if(resetButton) { break; } if(img_count == img_num) { eFusion->saveFilename = data_dir + "map"; eFusion->savePly(); break; } if(pangolin::Pushed(*gui->save)) { eFusion->savePly(); } TOCK("GUI"); } } ================================================ FILE: obj_pose_est/mapping/app/src/MainController.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include #include #include "Tools/GUI.h" #include "Tools/GroundTruthOdometry.h" #include "Tools/RawLogReader.h" #include "Tools/LiveLogReader.h" #include #include #include #include using namespace std; using namespace cv; #ifndef MAINCONTROLLER_H_ #define MAINCONTROLLER_H_ class MainController { public: MainController(int argc, char * argv[]); virtual ~MainController(); void launch(); private: void run(); void loadCalibration(const std::string & filename); bool good; ElasticFusion * eFusion; GUI * gui; GroundTruthOdometry * groundTruthOdometry; LogReader * logReader; int img_count; int img_num; bool iclnuim; std::string logFile; std::string poseFile; std::string data_dir; float confidence, depth, icp, icpErrThresh, covThresh, photoThresh, fernThresh; int timeDelta, icpCountThresh, start, end; bool fillIn, openLoop, reloc, frameskip, quiet, fastOdom, so3, rewind, frameToFrameRGB; int framesToSkip; bool streaming; bool resetButton; std::vector trajectory; Resize * resizeStream; }; #endif /* MAINCONTROLLER_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/CameraInterface.h ================================================ #pragma once #include #include #include #include #include "ThreadMutexObject.h" class CameraInterface { public: virtual ~CameraInterface() {} virtual bool ok() = 0; virtual std::string error() = 0; static const int numBuffers = 10; ThreadMutexObject latestDepthIndex; std::pair,int64_t> frameBuffers[numBuffers]; virtual void setAutoExposure(bool value) = 0; virtual void setAutoWhiteBalance(bool value) = 0; }; ================================================ FILE: obj_pose_est/mapping/app/src/Tools/GUI.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef GUI_H_ #define GUI_H_ #include #include #include #include #include #include #include #define GL_GPU_MEM_INFO_CURRENT_AVAILABLE_MEM_NVX 0x9049 class GUI { public: GUI(bool liveCap, bool showcaseMode) : showcaseMode(showcaseMode) { width = 1280; height = 980; panel = 205; width += panel; pangolin::Params windowParams; windowParams.Set("SAMPLE_BUFFERS", 0); windowParams.Set("SAMPLES", 0); pangolin::CreateWindowAndBind("Main", width, height, windowParams); glPixelStorei(GL_UNPACK_ALIGNMENT, 1); glPixelStorei(GL_PACK_ALIGNMENT, 1); //Internally render at 3840x2160 renderBuffer = new pangolin::GlRenderBuffer(3840, 2160), colorTexture = new GPUTexture(renderBuffer->width, renderBuffer->height, GL_RGBA32F, GL_LUMINANCE, GL_FLOAT, true); colorFrameBuffer = new pangolin::GlFramebuffer; colorFrameBuffer->AttachColour(*colorTexture->texture); colorFrameBuffer->AttachDepth(*renderBuffer); colorProgram = std::shared_ptr(loadProgramFromFile("draw_global_surface.vert", "draw_global_surface_phong.frag", "draw_global_surface.geom")); fxaaProgram = std::shared_ptr(loadProgramFromFile("empty.vert", "fxaa.frag", "quad.geom")); pangolin::SetFullscreen(showcaseMode); glEnable(GL_DEPTH_TEST); glDepthMask(GL_TRUE); glDepthFunc(GL_LESS); s_cam = pangolin::OpenGlRenderState(pangolin::ProjectionMatrix(640, 480, 420, 420, 320, 240, 0.1, 1000), pangolin::ModelViewLookAt(0, 0, -1, 0, 0, 1, pangolin::AxisNegY)); pangolin::Display("cam").SetBounds(0, 1.0f, 0, 1.0f, -640 / 480.0) .SetHandler(new pangolin::Handler3D(s_cam)); pangolin::Display(GPUTexture::RGB).SetAspect(640.0f / 480.0f); pangolin::Display(GPUTexture::DEPTH_NORM).SetAspect(640.0f / 480.0f); pangolin::Display("ModelImg").SetAspect(640.0f / 480.0f); pangolin::Display("Model").SetAspect(640.0f / 480.0f); std::vector labels; labels.push_back(std::string("residual")); labels.push_back(std::string("threshold")); resLog.SetLabels(labels); resPlot = new pangolin::Plotter(&resLog, 0, 300, 0, 0.0005, 30, 0.5); resPlot->Track("$i"); std::vector labels2; labels2.push_back(std::string("inliers")); labels2.push_back(std::string("threshold")); inLog.SetLabels(labels2); inPlot = new pangolin::Plotter(&inLog, 0, 300, 0, 40000, 30, 0.5); inPlot->Track("$i"); if(!showcaseMode) { pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, pangolin::Attach::Pix(panel)); pangolin::Display("multi").SetBounds(pangolin::Attach::Pix(0), 1 / 4.0f, showcaseMode ? 0 : pangolin::Attach::Pix(180), 1.0) .SetLayout(pangolin::LayoutEqualHorizontal) .AddDisplay(pangolin::Display(GPUTexture::RGB)) .AddDisplay(pangolin::Display(GPUTexture::DEPTH_NORM)) .AddDisplay(pangolin::Display("ModelImg")) .AddDisplay(pangolin::Display("Model")) .AddDisplay(*resPlot) .AddDisplay(*inPlot); } pause = new pangolin::Var("ui.Pause", false, true); step = new pangolin::Var("ui.Step", false, false); save = new pangolin::Var("ui.Save", false, false); reset = new pangolin::Var("ui.Reset", false, false); flipColors = new pangolin::Var("ui.Flip RGB", false, true); if(liveCap) { autoSettings = new pangolin::Var("ui.Auto Settings", true, true); } else { autoSettings = 0; } pyramid = new pangolin::Var("ui.Pyramid", true, true); so3 = new pangolin::Var("ui.SO(3)", true, true); frameToFrameRGB = new pangolin::Var("ui.Frame to frame RGB", false, true); fastOdom = new pangolin::Var("ui.Fast Odometry", false, true); rgbOnly = new pangolin::Var("ui.RGB only tracking", false, true); confidenceThreshold = new pangolin::Var("ui.Confidence threshold", 10.0, 0.0, 24.0); depthCutoff = new pangolin::Var("ui.Depth cutoff", 3.0, 0.0, 12.0); icpWeight = new pangolin::Var("ui.ICP weight", 10.0, 0.0, 100.0); followPose = new pangolin::Var("ui.Follow pose", true, true); drawRawCloud = new pangolin::Var("ui.Draw raw", false, true); drawFilteredCloud = new pangolin::Var("ui.Draw filtered", false, true); drawGlobalModel = new pangolin::Var("ui.Draw global model", true, true); drawUnstable = new pangolin::Var("ui.Draw unstable points", false, true); drawPoints = new pangolin::Var("ui.Draw points", false, true); drawColors = new pangolin::Var("ui.Draw colors", showcaseMode, true); drawFxaa = new pangolin::Var("ui.Draw FXAA", showcaseMode, true); drawWindow = new pangolin::Var("ui.Draw time window", false, true); drawNormals = new pangolin::Var("ui.Draw normals", false, true); drawTimes = new pangolin::Var("ui.Draw times", false, true); drawDefGraph = new pangolin::Var("ui.Draw deformation graph", false, true); drawFerns = new pangolin::Var("ui.Draw ferns", false, true); drawDeforms = new pangolin::Var("ui.Draw deformations", true, true); gpuMem = new pangolin::Var("ui.GPU memory free", 0); totalPoints = new pangolin::Var("ui.Total points", "0"); totalNodes = new pangolin::Var("ui.Total nodes", "0"); totalFerns = new pangolin::Var("ui.Total ferns", "0"); totalDefs = new pangolin::Var("ui.Total deforms", "0"); totalFernDefs = new pangolin::Var("ui.Total fern deforms", "0"); trackInliers = new pangolin::Var("ui.Inliers", "0"); trackRes = new pangolin::Var("ui.Residual", "0"); logProgress = new pangolin::Var("ui.Log", "0"); if(showcaseMode) { pangolin::RegisterKeyPressCallback(' ', pangolin::SetVarFunctor("ui.Reset", true)); } } virtual ~GUI() { delete pause; delete reset; delete inPlot; delete resPlot; if(autoSettings) { delete autoSettings; } delete step; delete save; delete trackInliers; delete trackRes; delete confidenceThreshold; delete totalNodes; delete drawWindow; delete so3; delete totalFerns; delete totalDefs; delete depthCutoff; delete logProgress; delete drawTimes; delete drawFxaa; delete fastOdom; delete icpWeight; delete pyramid; delete rgbOnly; delete totalFernDefs; delete drawFerns; delete followPose; delete drawDeforms; delete drawRawCloud; delete totalPoints; delete frameToFrameRGB; delete flipColors; delete drawFilteredCloud; delete drawNormals; delete drawColors; delete drawGlobalModel; delete drawUnstable; delete drawPoints; delete drawDefGraph; delete gpuMem; delete renderBuffer; delete colorFrameBuffer; delete colorTexture; } void preCall() { glClearColor(0.05 * !showcaseMode, 0.05 * !showcaseMode, 0.3 * !showcaseMode, 0.0f); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); width = pangolin::DisplayBase().v.w; height = pangolin::DisplayBase().v.h; pangolin::Display("cam").Activate(s_cam); } inline void drawFrustum(const Eigen::Matrix4f & pose) { if(showcaseMode) return; Eigen::Matrix3f K = Eigen::Matrix3f::Identity(); K(0, 0) = Intrinsics::getInstance().fx(); K(1, 1) = Intrinsics::getInstance().fy(); K(0, 2) = Intrinsics::getInstance().cx(); K(1, 2) = Intrinsics::getInstance().cy(); Eigen::Matrix3f Kinv = K.inverse(); pangolin::glDrawFrustum(Kinv, Resolution::getInstance().width(), Resolution::getInstance().height(), pose, 0.1f); } void displayImg(const std::string & id, GPUTexture * img) { if(showcaseMode) return; glDisable(GL_DEPTH_TEST); pangolin::Display(id).Activate(); img->texture->RenderToViewport(true); glEnable(GL_DEPTH_TEST); } void postCall() { GLint cur_avail_mem_kb = 0; glGetIntegerv(GL_GPU_MEM_INFO_CURRENT_AVAILABLE_MEM_NVX, &cur_avail_mem_kb); int memFree = cur_avail_mem_kb / 1024; gpuMem->operator=(memFree); pangolin::FinishFrame(); glFinish(); } void drawFXAA(pangolin::OpenGlMatrix mvp, pangolin::OpenGlMatrix mv, const std::pair & model, const float threshold, const int time, const int timeDelta, const bool invertNormals) { //First pass computes positions, colors and normals per pixel colorFrameBuffer->Bind(); glPushAttrib(GL_VIEWPORT_BIT); glViewport(0, 0, renderBuffer->width, renderBuffer->height); glClearColor(0.05 * !showcaseMode, 0.05 * !showcaseMode, 0.3 * !showcaseMode, 0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); colorProgram->Bind(); colorProgram->setUniform(Uniform("MVP", mvp)); colorProgram->setUniform(Uniform("threshold", threshold)); colorProgram->setUniform(Uniform("time", time)); colorProgram->setUniform(Uniform("timeDelta", timeDelta)); colorProgram->setUniform(Uniform("signMult", invertNormals ? 1.0f : -1.0f)); colorProgram->setUniform(Uniform("colorType", (drawNormals->Get() ? 1 : drawColors->Get() ? 2 : drawTimes->Get() ? 3 : 0))); colorProgram->setUniform(Uniform("unstable", drawUnstable->Get())); colorProgram->setUniform(Uniform("drawWindow", drawWindow->Get())); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); //This is for the point shader colorProgram->setUniform(Uniform("pose", pose)); Eigen::Matrix4f modelView = mv; Eigen::Vector3f lightpos = modelView.topRightCorner(3, 1); colorProgram->setUniform(Uniform("lightpos", lightpos)); glBindBuffer(GL_ARRAY_BUFFER, model.first); glEnableVertexAttribArray(0); glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, 0); glEnableVertexAttribArray(1); glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 1)); glEnableVertexAttribArray(2); glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, Vertex::SIZE, reinterpret_cast(sizeof(Eigen::Vector4f) * 2)); glDrawTransformFeedback(GL_POINTS, model.second); glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); glDisableVertexAttribArray(2); glBindBuffer(GL_ARRAY_BUFFER, 0); colorFrameBuffer->Unbind(); colorProgram->Unbind(); glPopAttrib(); fxaaProgram->Bind(); glActiveTexture(GL_TEXTURE0); glBindTexture(GL_TEXTURE_2D, colorTexture->texture->tid); Eigen::Vector2f resolution(renderBuffer->width, renderBuffer->height); fxaaProgram->setUniform(Uniform("tex", 0)); fxaaProgram->setUniform(Uniform("resolution", resolution)); glDrawArrays(GL_POINTS, 0, 1); fxaaProgram->Unbind(); glBindFramebuffer(GL_READ_FRAMEBUFFER, colorFrameBuffer->fbid); glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0); glBlitFramebuffer(0, 0, renderBuffer->width, renderBuffer->height, 0, 0, width, height, GL_DEPTH_BUFFER_BIT, GL_NEAREST); glBindTexture(GL_TEXTURE_2D, 0); glFinish(); } bool showcaseMode; int width; int height; int panel; pangolin::Var * pause, * step, * save, * reset, * flipColors, * rgbOnly, * pyramid, * so3, * frameToFrameRGB, * fastOdom, * followPose, * drawRawCloud, * drawFilteredCloud, * drawNormals, * autoSettings, * drawDefGraph, * drawColors, * drawFxaa, * drawGlobalModel, * drawUnstable, * drawPoints, * drawTimes, * drawFerns, * drawDeforms, * drawWindow; pangolin::Var * gpuMem; pangolin::Var * totalPoints, * totalNodes, * totalFerns, * totalDefs, * totalFernDefs, * trackInliers, * trackRes, * logProgress; pangolin::Var * confidenceThreshold, * depthCutoff, * icpWeight; pangolin::DataLog resLog, inLog; pangolin::Plotter * resPlot, * inPlot; pangolin::OpenGlRenderState s_cam; pangolin::GlRenderBuffer * renderBuffer; pangolin::GlFramebuffer * colorFrameBuffer; GPUTexture * colorTexture; std::shared_ptr colorProgram; std::shared_ptr fxaaProgram; }; #endif /* GUI_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/GroundTruthOdometry.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "GroundTruthOdometry.h" GroundTruthOdometry::GroundTruthOdometry(const std::string & filename) : last_utime(0) { loadTrajectory(filename); } GroundTruthOdometry::~GroundTruthOdometry() { } void GroundTruthOdometry::loadTrajectory(const std::string & filename) { std::ifstream file; std::string line; file.open(filename.c_str()); while (!file.eof()) { unsigned long long int utime; float x, y, z, qx, qy, qz, qw; std::getline(file, line); int n = sscanf(line.c_str(), "%llu,%f,%f,%f,%f,%f,%f,%f", &utime, &x, &y, &z, &qx, &qy, &qz, &qw); if(file.eof()) break; assert(n == 8); Eigen::Quaternionf q(qw, qx, qy, qz); Eigen::Vector3f t(x, y, z); Eigen::Isometry3f T; T.setIdentity(); T.pretranslate(t).rotate(q); camera_trajectory[utime] = T; } } Eigen::Matrix4f GroundTruthOdometry::getTransformation(uint64_t timestamp) { Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); if(last_utime != 0) { std::map::const_iterator it = camera_trajectory.find(last_utime); if (it == camera_trajectory.end()) { last_utime = timestamp; return pose; } //Poses are stored in the file in iSAM basis, undo it Eigen::Matrix4f M; M << 0, 0, 1, 0, -1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 0, 1; pose = M.inverse() * camera_trajectory[timestamp] * M; } else { std::map::const_iterator it = camera_trajectory.find(timestamp); Eigen::Isometry3f ident = it->second; pose = Eigen::Matrix4f::Identity(); camera_trajectory[last_utime] = ident; } last_utime = timestamp; return pose; } Eigen::MatrixXd GroundTruthOdometry::getCovariance() { Eigen::MatrixXd cov(6, 6); cov.setIdentity(); cov(0, 0) = 0.1; cov(1, 1) = 0.1; cov(2, 2) = 0.1; cov(3, 3) = 0.5; cov(4, 4) = 0.5; cov(5, 5) = 0.5; return cov; } ================================================ FILE: obj_pose_est/mapping/app/src/Tools/GroundTruthOdometry.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef GROUNDTRUTHODOMETRY_H_ #define GROUNDTRUTHODOMETRY_H_ #ifdef WIN32 # include #endif #include #include #include #include #include #include #include #include #include class GroundTruthOdometry { public: GroundTruthOdometry(const std::string & filename); virtual ~GroundTruthOdometry(); Eigen::Matrix4f getTransformation(uint64_t timestamp); Eigen::MatrixXd getCovariance(); private: void loadTrajectory(const std::string & filename); std::map, Eigen::aligned_allocator > > camera_trajectory; uint64_t last_utime; }; #endif /* GROUNDTRUTHODOMETRY_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/JPEGLoader.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef TOOLS_JPEGLOADER_H_ #define TOOLS_JPEGLOADER_H_ extern "C" { #include "jpeglib.h" } #include #include static void jpegFail(j_common_ptr cinfo) { assert(false && "JPEG decoding error!"); } static void doNothing(j_decompress_ptr) { } class JPEGLoader { public: JPEGLoader() {} void readData(unsigned char * src, const int numBytes, unsigned char * data) { jpeg_decompress_struct cinfo; // IJG JPEG codec structure jpeg_error_mgr errorMgr; errorMgr.error_exit = jpegFail; cinfo.err = jpeg_std_error(&errorMgr); jpeg_create_decompress(&cinfo); jpeg_source_mgr srcMgr; cinfo.src = &srcMgr; // Prepare for suspending reader srcMgr.init_source = doNothing; srcMgr.resync_to_restart = jpeg_resync_to_restart; srcMgr.term_source = doNothing; srcMgr.next_input_byte = src; srcMgr.bytes_in_buffer = numBytes; jpeg_read_header(&cinfo, TRUE); jpeg_calc_output_dimensions(&cinfo); jpeg_start_decompress(&cinfo); int width = cinfo.output_width; int height = cinfo.output_height; JSAMPARRAY buffer = (*cinfo.mem->alloc_sarray)((j_common_ptr)&cinfo, JPOOL_IMAGE, width * 4, 1); for(; height--; data += (width * 3)) { jpeg_read_scanlines(&cinfo, buffer, 1); unsigned char * bgr = (unsigned char *)buffer[0]; unsigned char * rgb = (unsigned char *)data; for(int i = 0; i < width; i++, bgr += 3, rgb += 3) { unsigned char t0 = bgr[0], t1 = bgr[1], t2 = bgr[2]; rgb[2] = t0; rgb[1] = t1; rgb[0] = t2; } } jpeg_finish_decompress(&cinfo); jpeg_destroy_decompress(&cinfo); } }; #endif /* TOOLS_JPEGLOADER_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/LiveLogReader.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "LiveLogReader.h" #include "OpenNI2Interface.h" #include "RealSenseInterface.h" LiveLogReader::LiveLogReader(std::string file, bool flipColors, CameraType type) : LogReader(file, flipColors), lastFrameTime(-1), lastGot(-1) { std::cout << "Creating live capture... "; std::cout.flush(); if(type == CameraType::OpenNI2) cam = new OpenNI2Interface(Resolution::getInstance().width(),Resolution::getInstance().height()); else if(type == CameraType::RealSense) cam = new RealSenseInterface(Resolution::getInstance().width(), Resolution::getInstance().height()); else cam = nullptr; decompressionBufferDepth = new Bytef[Resolution::getInstance().numPixels() * 2]; decompressionBufferImage = new Bytef[Resolution::getInstance().numPixels() * 3]; if(!cam || !cam->ok()) { std::cout << "failed!" << std::endl; std::cout << cam->error(); } else { std::cout << "success!" << std::endl; std::cout << "Waiting for first frame"; std::cout.flush(); int lastDepth = cam->latestDepthIndex.getValue(); do { std::this_thread::sleep_for(std::chrono::microseconds(33333)); std::cout << "."; std::cout.flush(); lastDepth = cam->latestDepthIndex.getValue(); } while(lastDepth == -1); std::cout << " got it!" << std::endl; } } LiveLogReader::~LiveLogReader() { delete [] decompressionBufferDepth; delete [] decompressionBufferImage; delete cam; } void LiveLogReader::getNext() { int lastDepth = cam->latestDepthIndex.getValue(); assert(lastDepth != -1); int bufferIndex = lastDepth % CameraInterface::numBuffers; if(bufferIndex == lastGot) { return; } if(lastFrameTime == cam->frameBuffers[bufferIndex].second) { return; } memcpy(&decompressionBufferDepth[0], cam->frameBuffers[bufferIndex].first.first, Resolution::getInstance().numPixels() * 2); memcpy(&decompressionBufferImage[0], cam->frameBuffers[bufferIndex].first.second,Resolution::getInstance().numPixels() * 3); lastFrameTime = cam->frameBuffers[bufferIndex].second; timestamp = lastFrameTime; rgb = (unsigned char *)&decompressionBufferImage[0]; depth = (unsigned short *)&decompressionBufferDepth[0]; imageReadBuffer = 0; depthReadBuffer = 0; imageSize = Resolution::getInstance().numPixels() * 3; depthSize = Resolution::getInstance().numPixels() * 2; if(flipColors) { for(int i = 0; i < Resolution::getInstance().numPixels() * 3; i += 3) { std::swap(rgb[i + 0], rgb[i + 2]); } } } const std::string LiveLogReader::getFile() { return Parse::get().baseDir().append("live"); } int LiveLogReader::getNumFrames() { return std::numeric_limits::max(); } bool LiveLogReader::hasMore() { return true; } void LiveLogReader::setAuto(bool value) { cam->setAutoExposure(value); cam->setAutoWhiteBalance(value); } ================================================ FILE: obj_pose_est/mapping/app/src/Tools/LiveLogReader.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef LIVELOGREADER_H_ #define LIVELOGREADER_H_ #include #include #ifndef WIN32 # include #endif #include #include #include #include #include "LogReader.h" #include "CameraInterface.h" class LiveLogReader : public LogReader { public: enum CameraType { OpenNI2,RealSense }; LiveLogReader(std::string file, bool flipColors, CameraType type); virtual ~LiveLogReader(); void getNext(); int getNumFrames(); bool hasMore(); bool rewound() { return false; } void rewind() { } void getBack() { } void fastForward(int frame) { } const std::string getFile(); void setAuto(bool value); CameraInterface * cam; private: int64_t lastFrameTime; int lastGot; }; #endif /* LIVELOGREADER_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/LogReader.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef LOGREADER_H_ #define LOGREADER_H_ #ifdef WIN32 # include #endif #include #if (defined WIN32) && (defined FAR) # undef FAR #endif #include #ifndef WIN32 # include #endif #include #include #include "JPEGLoader.h" class LogReader { public: LogReader(std::string file, bool flipColors) : flipColors(flipColors), timestamp(0), depth(0), rgb(0), currentFrame(0), decompressionBufferDepth(0), decompressionBufferImage(0), file(file), width(Resolution::getInstance().width()), height(Resolution::getInstance().height()), numPixels(width * height) {} virtual ~LogReader() {} virtual void getNext() = 0; virtual int getNumFrames() = 0; virtual bool hasMore() = 0; virtual bool rewound() = 0; virtual void rewind() = 0; virtual void getBack() = 0; virtual void fastForward(int frame) = 0; virtual const std::string getFile() = 0; virtual void setAuto(bool value) = 0; bool flipColors; int64_t timestamp; unsigned short * depth; unsigned char * rgb; int currentFrame; protected: Bytef * decompressionBufferDepth; Bytef * decompressionBufferImage; unsigned char * depthReadBuffer; unsigned char * imageReadBuffer; int32_t depthSize; int32_t imageSize; const std::string file; FILE * fp; int32_t numFrames; int width; int height; int numPixels; JPEGLoader jpeg; }; #endif /* LOGREADER_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/OpenNI2Interface.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "OpenNI2Interface.h" OpenNI2Interface::OpenNI2Interface(int inWidth, int inHeight, int fps) : width(inWidth), height(inHeight), fps(fps), initSuccessful(true) { //Setup openni::Status rc = openni::STATUS_OK; const char * deviceURI = openni::ANY_DEVICE; rc = openni::OpenNI::initialize(); std::string errorString(openni::OpenNI::getExtendedError()); if(errorString.length() > 0) { errorText.append(errorString); initSuccessful = false; } else { rc = device.open(deviceURI); if (rc != openni::STATUS_OK) { errorText.append(openni::OpenNI::getExtendedError()); openni::OpenNI::shutdown(); initSuccessful = false; } else { openni::VideoMode depthMode; depthMode.setFps(fps); depthMode.setPixelFormat(openni::PIXEL_FORMAT_DEPTH_1_MM); depthMode.setResolution(width, height); openni::VideoMode colorMode; colorMode.setFps(fps); colorMode.setPixelFormat(openni::PIXEL_FORMAT_RGB888); colorMode.setResolution(width, height); rc = depthStream.create(device, openni::SENSOR_DEPTH); if (rc == openni::STATUS_OK) { depthStream.setVideoMode(depthMode); rc = depthStream.start(); if (rc != openni::STATUS_OK) { errorText.append(openni::OpenNI::getExtendedError()); depthStream.destroy(); initSuccessful = false; } } else { errorText.append(openni::OpenNI::getExtendedError()); initSuccessful = false; } rc = rgbStream.create(device, openni::SENSOR_COLOR); if (rc == openni::STATUS_OK) { rgbStream.setVideoMode(colorMode); rc = rgbStream.start(); if (rc != openni::STATUS_OK) { errorText.append(openni::OpenNI::getExtendedError()); rgbStream.destroy(); initSuccessful = false; } } else { errorText.append(openni::OpenNI::getExtendedError()); initSuccessful = false; } if (!depthStream.isValid() || !rgbStream.isValid()) { errorText.append(openni::OpenNI::getExtendedError()); openni::OpenNI::shutdown(); initSuccessful = false; } if(initSuccessful) { //For printing out formatMap[openni::PIXEL_FORMAT_DEPTH_1_MM] = "1mm"; formatMap[openni::PIXEL_FORMAT_DEPTH_100_UM] = "100um"; formatMap[openni::PIXEL_FORMAT_SHIFT_9_2] = "Shift 9 2"; formatMap[openni::PIXEL_FORMAT_SHIFT_9_3] = "Shift 9 3"; formatMap[openni::PIXEL_FORMAT_RGB888] = "RGB888"; formatMap[openni::PIXEL_FORMAT_YUV422] = "YUV422"; formatMap[openni::PIXEL_FORMAT_GRAY8] = "GRAY8"; formatMap[openni::PIXEL_FORMAT_GRAY16] = "GRAY16"; formatMap[openni::PIXEL_FORMAT_JPEG] = "JPEG"; assert(findMode(width, height, fps) && "Sorry, mode not supported!"); latestDepthIndex.assign(-1); latestRgbIndex.assign(-1); for(int i = 0; i < numBuffers; i++) { uint8_t * newImage = (uint8_t *)calloc(width * height * 3, sizeof(uint8_t)); rgbBuffers[i] = std::pair(newImage, 0); } for(int i = 0; i < numBuffers; i++) { uint8_t * newDepth = (uint8_t *)calloc(width * height * 2, sizeof(uint8_t)); uint8_t * newImage = (uint8_t *)calloc(width * height * 3, sizeof(uint8_t)); frameBuffers[i] = std::pair, int64_t>(std::pair(newDepth, newImage), 0); } rgbCallback = new RGBCallback(lastRgbTime, latestRgbIndex, rgbBuffers); depthCallback = new DepthCallback(lastDepthTime, latestDepthIndex, latestRgbIndex, rgbBuffers, frameBuffers); depthStream.setMirroringEnabled(false); rgbStream.setMirroringEnabled(false); device.setDepthColorSyncEnabled(true); device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR); setAutoExposure(true); setAutoWhiteBalance(true); rgbStream.addNewFrameListener(rgbCallback); depthStream.addNewFrameListener(depthCallback); } } } } OpenNI2Interface::~OpenNI2Interface() { if(initSuccessful) { rgbStream.removeNewFrameListener(rgbCallback); depthStream.removeNewFrameListener(depthCallback); depthStream.stop(); rgbStream.stop(); depthStream.destroy(); rgbStream.destroy(); device.close(); openni::OpenNI::shutdown(); for(int i = 0; i < numBuffers; i++) { free(rgbBuffers[i].first); } for(int i = 0; i < numBuffers; i++) { free(frameBuffers[i].first.first); free(frameBuffers[i].first.second); } delete rgbCallback; delete depthCallback; } } bool OpenNI2Interface::findMode(int x, int y, int fps) { const openni::Array & depthModes = depthStream.getSensorInfo().getSupportedVideoModes(); bool found = false; for(int i = 0; i < depthModes.getSize(); i++) { if(depthModes[i].getResolutionX() == x && depthModes[i].getResolutionY() == y && depthModes[i].getFps() == fps) { found = true; break; } } if(!found) { return false; } found = false; const openni::Array & rgbModes = rgbStream.getSensorInfo().getSupportedVideoModes(); for(int i = 0; i < rgbModes.getSize(); i++) { if(rgbModes[i].getResolutionX() == x && rgbModes[i].getResolutionY() == y && rgbModes[i].getFps() == fps) { found = true; break; } } return found; } void OpenNI2Interface::printModes() { const openni::Array & depthModes = depthStream.getSensorInfo().getSupportedVideoModes(); openni::VideoMode currentDepth = depthStream.getVideoMode(); std::cout << "Depth Modes: (" << currentDepth.getResolutionX() << "x" << currentDepth.getResolutionY() << " @ " << currentDepth.getFps() << "fps " << formatMap[currentDepth.getPixelFormat()] << ")" << std::endl; for(int i = 0; i < depthModes.getSize(); i++) { std::cout << depthModes[i].getResolutionX() << "x" << depthModes[i].getResolutionY() << " @ " << depthModes[i].getFps() << "fps " << formatMap[depthModes[i].getPixelFormat()] << std::endl; } const openni::Array & rgbModes = rgbStream.getSensorInfo().getSupportedVideoModes(); openni::VideoMode currentRGB = depthStream.getVideoMode(); std::cout << "RGB Modes: (" << currentRGB.getResolutionX() << "x" << currentRGB.getResolutionY() << " @ " << currentRGB.getFps() << "fps " << formatMap[currentRGB.getPixelFormat()] << ")" << std::endl; for(int i = 0; i < rgbModes.getSize(); i++) { std::cout << rgbModes[i].getResolutionX() << "x" << rgbModes[i].getResolutionY() << " @ " << rgbModes[i].getFps() << "fps " << formatMap[rgbModes[i].getPixelFormat()] << std::endl; } } void OpenNI2Interface::setAutoExposure(bool value) { rgbStream.getCameraSettings()->setAutoExposureEnabled(value); } void OpenNI2Interface::setAutoWhiteBalance(bool value) { rgbStream.getCameraSettings()->setAutoWhiteBalanceEnabled(value); } bool OpenNI2Interface::getAutoExposure() { return rgbStream.getCameraSettings()->getAutoExposureEnabled(); } bool OpenNI2Interface::getAutoWhiteBalance() { return rgbStream.getCameraSettings()->getAutoWhiteBalanceEnabled(); } ================================================ FILE: obj_pose_est/mapping/app/src/Tools/OpenNI2Interface.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef OPENNI2INTERFACE_H_ #define OPENNI2INTERFACE_H_ #include #include #include #include #include #include #include "ThreadMutexObject.h" #include "CameraInterface.h" class OpenNI2Interface : public CameraInterface { public: OpenNI2Interface(int inWidth = 640, int inHeight = 480, int fps = 30); virtual ~OpenNI2Interface(); const int width, height, fps; void printModes(); bool findMode(int x, int y, int fps); virtual void setAutoExposure(bool value); virtual void setAutoWhiteBalance(bool value); bool getAutoExposure(); bool getAutoWhiteBalance(); virtual bool ok() { return initSuccessful; } virtual std::string error() { errorText.erase(std::remove_if(errorText.begin(), errorText.end(), &OpenNI2Interface::isTab), errorText.end()); return errorText; } class RGBCallback : public openni::VideoStream::NewFrameListener { public: RGBCallback(int64_t & lastRgbTime, ThreadMutexObject & latestRgbIndex, std::pair * rgbBuffers) : lastRgbTime(lastRgbTime), latestRgbIndex(latestRgbIndex), rgbBuffers(rgbBuffers) {} virtual ~RGBCallback() {} void onNewFrame(openni::VideoStream& stream) { stream.readFrame(&frame); lastRgbTime = std::chrono::duration_cast( std::chrono::system_clock::now().time_since_epoch()).count(); int bufferIndex = (latestRgbIndex.getValue() + 1) % numBuffers; memcpy(rgbBuffers[bufferIndex].first, frame.getData(), frame.getWidth() * frame.getHeight() * 3); rgbBuffers[bufferIndex].second = lastRgbTime; latestRgbIndex++; } private: openni::VideoFrameRef frame; int64_t & lastRgbTime; ThreadMutexObject & latestRgbIndex; std::pair * rgbBuffers; }; class DepthCallback : public openni::VideoStream::NewFrameListener { public: DepthCallback(int64_t & lastDepthTime, ThreadMutexObject & latestDepthIndex, ThreadMutexObject & latestRgbIndex, std::pair * rgbBuffers, std::pair, int64_t> * frameBuffers) : lastDepthTime(lastDepthTime), latestDepthIndex(latestDepthIndex), latestRgbIndex(latestRgbIndex), rgbBuffers(rgbBuffers), frameBuffers(frameBuffers) {} virtual ~DepthCallback() {} void onNewFrame(openni::VideoStream& stream) { stream.readFrame(&frame); lastDepthTime = std::chrono::duration_cast( std::chrono::system_clock::now().time_since_epoch()).count(); int bufferIndex = (latestDepthIndex.getValue() + 1) % numBuffers; memcpy(frameBuffers[bufferIndex].first.first, frame.getData(), frame.getWidth() * frame.getHeight() * 2); frameBuffers[bufferIndex].second = lastDepthTime; int lastImageVal = latestRgbIndex.getValue(); if(lastImageVal == -1) { return; } lastImageVal %= numBuffers; memcpy(frameBuffers[bufferIndex].first.second, rgbBuffers[lastImageVal].first, frame.getWidth() * frame.getHeight() * 3); latestDepthIndex++; } private: openni::VideoFrameRef frame; int64_t & lastDepthTime; ThreadMutexObject & latestDepthIndex; ThreadMutexObject & latestRgbIndex; std::pair * rgbBuffers; std::pair, int64_t> * frameBuffers; }; private: openni::Device device; openni::VideoStream depthStream; openni::VideoStream rgbStream; //Map for formats from OpenNI2 std::map formatMap; int64_t lastRgbTime; int64_t lastDepthTime; ThreadMutexObject latestRgbIndex; std::pair rgbBuffers[numBuffers]; RGBCallback * rgbCallback; DepthCallback * depthCallback; bool initSuccessful; std::string errorText; //For removing tabs from OpenNI's error messages static bool isTab(char c) { switch(c) { case '\t': return true; default: return false; } } }; #endif /* OPENNI2INTERFACE_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/RawLogReader.cpp ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #include "RawLogReader.h" RawLogReader::RawLogReader(std::string file, bool flipColors) : LogReader(file, flipColors) { assert(pangolin::FileExists(file.c_str())); fp = fopen(file.c_str(), "rb"); currentFrame = 0; auto tmp = fread(&numFrames,sizeof(int32_t),1,fp); assert(tmp); depthReadBuffer = new unsigned char[numPixels * 2]; imageReadBuffer = new unsigned char[numPixels * 3]; decompressionBufferDepth = new Bytef[Resolution::getInstance().numPixels() * 2]; decompressionBufferImage = new Bytef[Resolution::getInstance().numPixels() * 3]; } RawLogReader::~RawLogReader() { delete [] depthReadBuffer; delete [] imageReadBuffer; delete [] decompressionBufferDepth; delete [] decompressionBufferImage; fclose(fp); } void RawLogReader::getBack() { assert(filePointers.size() > 0); fseek(fp, filePointers.top(), SEEK_SET); filePointers.pop(); getCore(); } void RawLogReader::getNext() { filePointers.push(ftell(fp)); getCore(); } void RawLogReader::getCore() { auto tmp = fread(×tamp,sizeof(int64_t),1,fp); assert(tmp); tmp = fread(&depthSize,sizeof(int32_t),1,fp); assert(tmp); tmp = fread(&imageSize,sizeof(int32_t),1,fp); assert(tmp); tmp = fread(depthReadBuffer,depthSize,1,fp); assert(tmp); if(imageSize > 0) { tmp = fread(imageReadBuffer,imageSize,1,fp); assert(tmp); } if(depthSize == numPixels * 2) { memcpy(&decompressionBufferDepth[0], depthReadBuffer, numPixels * 2); } else { unsigned long decompLength = numPixels * 2; uncompress(&decompressionBufferDepth[0], (unsigned long *)&decompLength, (const Bytef *)depthReadBuffer, depthSize); } if(imageSize == numPixels * 3) { memcpy(&decompressionBufferImage[0], imageReadBuffer, numPixels * 3); } else if(imageSize > 0) { jpeg.readData(imageReadBuffer, imageSize, (unsigned char *)&decompressionBufferImage[0]); } else { memset(&decompressionBufferImage[0], 0, numPixels * 3); } depth = (unsigned short *)decompressionBufferDepth; rgb = (unsigned char *)&decompressionBufferImage[0]; if(flipColors) { for(int i = 0; i < Resolution::getInstance().numPixels() * 3; i += 3) { std::swap(rgb[i + 0], rgb[i + 2]); } } currentFrame++; } void RawLogReader::fastForward(int frame) { while(currentFrame < frame && hasMore()) { filePointers.push(ftell(fp)); auto tmp = fread(×tamp,sizeof(int64_t),1,fp); assert(tmp); tmp = fread(&depthSize,sizeof(int32_t),1,fp); assert(tmp); tmp = fread(&imageSize,sizeof(int32_t),1,fp); assert(tmp); tmp = fread(depthReadBuffer,depthSize,1,fp); assert(tmp); if(imageSize > 0) { tmp = fread(imageReadBuffer,imageSize,1,fp); assert(tmp); } currentFrame++; } } int RawLogReader::getNumFrames() { return numFrames; } bool RawLogReader::hasMore() { return currentFrame + 1 < numFrames; } void RawLogReader::rewind() { if (filePointers.size() != 0) { std::stack empty; std::swap(empty, filePointers); } fclose(fp); fp = fopen(file.c_str(), "rb"); auto tmp = fread(&numFrames,sizeof(int32_t),1,fp); assert(tmp); currentFrame = 0; } bool RawLogReader::rewound() { return filePointers.size() == 0; } const std::string RawLogReader::getFile() { return file; } void RawLogReader::setAuto(bool value) { } ================================================ FILE: obj_pose_est/mapping/app/src/Tools/RawLogReader.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef RAWLOGREADER_H_ #define RAWLOGREADER_H_ #include #include #include #include "LogReader.h" #include #include #include #include #include #include class RawLogReader : public LogReader { public: RawLogReader(std::string file, bool flipColors); virtual ~RawLogReader(); void getNext(); void getBack(); int getNumFrames(); bool hasMore(); bool rewound(); void rewind(); void fastForward(int frame); const std::string getFile(); void setAuto(bool value); std::stack filePointers; private: void getCore(); }; #endif /* RAWLOGREADER_H_ */ ================================================ FILE: obj_pose_est/mapping/app/src/Tools/RealSenseInterface.cpp ================================================ #include "RealSenseInterface.h" #include #ifdef WITH_REALSENSE RealSenseInterface::RealSenseInterface(int inWidth,int inHeight,int inFps) : width(inWidth), height(inHeight), fps(inFps), dev(nullptr), initSuccessful(true) { if(ctx.get_device_count() == 0) { errorText = "No device connected."; initSuccessful = false; return; } dev = ctx.get_device(0); dev->enable_stream(rs::stream::depth,width,height,rs::format::z16,fps); dev->enable_stream(rs::stream::color,width,height,rs::format::rgb8,fps); latestDepthIndex.assign(-1); latestRgbIndex.assign(-1); for(int i = 0; i < numBuffers; i++) { uint8_t * newImage = (uint8_t *)calloc(width * height * 3,sizeof(uint8_t)); rgbBuffers[i] = std::pair(newImage,0); } for(int i = 0; i < numBuffers; i++) { uint8_t * newDepth = (uint8_t *)calloc(width * height * 2,sizeof(uint8_t)); uint8_t * newImage = (uint8_t *)calloc(width * height * 3,sizeof(uint8_t)); frameBuffers[i] = std::pair,int64_t>(std::pair(newDepth,newImage),0); } setAutoExposure(true); setAutoWhiteBalance(true); rgbCallback = new RGBCallback(lastRgbTime, latestRgbIndex, rgbBuffers); depthCallback = new DepthCallback(lastDepthTime, latestDepthIndex, latestRgbIndex, rgbBuffers, frameBuffers); dev->set_frame_callback(rs::stream::depth,*depthCallback); dev->set_frame_callback(rs::stream::color,*rgbCallback); dev->start(); } RealSenseInterface::~RealSenseInterface() { if(initSuccessful) { dev->stop(); for(int i = 0; i < numBuffers; i++) { free(rgbBuffers[i].first); } for(int i = 0; i < numBuffers; i++) { free(frameBuffers[i].first.first); free(frameBuffers[i].first.second); } delete rgbCallback; delete depthCallback; } } void RealSenseInterface::setAutoExposure(bool value) { dev->set_option(rs::option::color_enable_auto_exposure,value); } void RealSenseInterface::setAutoWhiteBalance(bool value) { dev->set_option(rs::option::color_enable_auto_white_balance,value); } bool RealSenseInterface::getAutoExposure() { return dev->get_option(rs::option::color_enable_auto_exposure); } bool RealSenseInterface::getAutoWhiteBalance() { return dev->get_option(rs::option::color_enable_auto_white_balance); } #else RealSenseInterface::RealSenseInterface(int inWidth,int inHeight,int inFps) : width(inWidth), height(inHeight), fps(inFps), initSuccessful(false) { errorText = "Compiled without Intel RealSense library"; } RealSenseInterface::~RealSenseInterface() { } void RealSenseInterface::setAutoExposure(bool value) { } void RealSenseInterface::setAutoWhiteBalance(bool value) { } bool RealSenseInterface::getAutoExposure() { return false; } bool RealSenseInterface::getAutoWhiteBalance() { return false; } #endif ================================================ FILE: obj_pose_est/mapping/app/src/Tools/RealSenseInterface.h ================================================ #pragma once #include #include #include #include #ifdef WITH_REALSENSE #include "librealsense/rs.hpp" #endif #include "ThreadMutexObject.h" #include "CameraInterface.h" class RealSenseInterface : public CameraInterface { public: RealSenseInterface(int width = 640,int height = 480,int fps = 30); virtual ~RealSenseInterface(); const int width,height,fps; bool getAutoExposure(); bool getAutoWhiteBalance(); virtual void setAutoExposure(bool value); virtual void setAutoWhiteBalance(bool value); virtual bool ok() { return initSuccessful; } virtual std::string error() { return errorText; } #ifdef WITH_REALSENSE struct RGBCallback { public: RGBCallback(int64_t & lastRgbTime, ThreadMutexObject & latestRgbIndex, std::pair * rgbBuffers) : lastRgbTime(lastRgbTime), latestRgbIndex(latestRgbIndex), rgbBuffers(rgbBuffers) { } void operator()(rs::frame frame) { lastRgbTime = std::chrono::duration_cast( std::chrono::system_clock::now().time_since_epoch()).count(); int bufferIndex = (latestRgbIndex.getValue() + 1) % numBuffers; memcpy(rgbBuffers[bufferIndex].first,frame.get_data(), frame.get_width() * frame.get_height() * 3); rgbBuffers[bufferIndex].second = lastRgbTime; latestRgbIndex++; } private: int64_t & lastRgbTime; ThreadMutexObject & latestRgbIndex; std::pair * rgbBuffers; }; struct DepthCallback { public: DepthCallback(int64_t & lastDepthTime, ThreadMutexObject & latestDepthIndex, ThreadMutexObject & latestRgbIndex, std::pair * rgbBuffers, std::pair,int64_t> * frameBuffers) : lastDepthTime(lastDepthTime), latestDepthIndex(latestDepthIndex), latestRgbIndex(latestRgbIndex), rgbBuffers(rgbBuffers), frameBuffers(frameBuffers) { } void operator()(rs::frame frame) { lastDepthTime = std::chrono::duration_cast( std::chrono::system_clock::now().time_since_epoch()).count(); int bufferIndex = (latestDepthIndex.getValue() + 1) % numBuffers; // The multiplication by 2 is here because the depth is actually uint16_t memcpy(frameBuffers[bufferIndex].first.first,frame.get_data(), frame.get_width() * frame.get_height() * 2); frameBuffers[bufferIndex].second = lastDepthTime; int lastImageVal = latestRgbIndex.getValue(); if(lastImageVal == -1) { return; } lastImageVal %= numBuffers; memcpy(frameBuffers[bufferIndex].first.second,rgbBuffers[lastImageVal].first, frame.get_width() * frame.get_height() * 3); latestDepthIndex++; } private: int64_t & lastDepthTime; ThreadMutexObject & latestDepthIndex; ThreadMutexObject & latestRgbIndex; std::pair * rgbBuffers; std::pair,int64_t> * frameBuffers; }; #endif private: #ifdef WITH_REALSENSE rs::device *dev; rs::context ctx; RGBCallback * rgbCallback; DepthCallback * depthCallback; #endif bool initSuccessful; std::string errorText; ThreadMutexObject latestRgbIndex; std::pair rgbBuffers[numBuffers]; int64_t lastRgbTime; int64_t lastDepthTime; }; ================================================ FILE: obj_pose_est/mapping/app/src/Tools/ThreadMutexObject.h ================================================ /* * This file is part of ElasticFusion. * * Copyright (C) 2015 Imperial College London * * The use of the code within this file and all code within files that * make up the software that is ElasticFusion is permitted for * non-commercial purposes only. The full terms and conditions that * apply to the code within this file are detailed within the LICENSE.txt * file and at * unless explicitly stated. By downloading this file you agree to * comply with these terms. * * If you wish to use any of this code for commercial purposes then * please email researchcontracts.engineering@imperial.ac.uk. * */ #ifndef THREADMUTEXOBJECT_H_ #define THREADMUTEXOBJECT_H_ #include #include #include #include template class ThreadMutexObject { public: ThreadMutexObject() {} ThreadMutexObject(T initialValue) : object(initialValue), lastCopy(initialValue) {} void assign(T newValue) { mutex.lock(); object = lastCopy = newValue; mutex.unlock(); } std::mutex & getMutex() { return mutex; } T & getReference() { return object; } void assignAndNotifyAll(T newValue) { mutex.lock(); object = newValue; signal.notify_all(); mutex.unlock(); } void notifyAll() { mutex.lock(); signal.notify_all(); mutex.unlock(); } T getValue() { mutex.lock(); lastCopy = object; mutex.unlock(); return lastCopy; } T waitForSignal() { mutex.lock(); signal.wait(mutex); lastCopy = object; mutex.unlock(); return lastCopy; } T getValueWait(int wait = 33000) { std::this_thread::sleep_for(std::chrono::microseconds(wait)); mutex.lock(); lastCopy = object; mutex.unlock(); return lastCopy; } T & getReferenceWait(int wait = 33000) { std::this_thread::sleep_for(std::chrono::microseconds(wait)); mutex.lock(); lastCopy = object; mutex.unlock(); return lastCopy; } void operator++(int) { mutex.lock(); object++; mutex.unlock(); } private: T object; T lastCopy; std::mutex mutex; std::condition_variable_any signal; }; #endif /* THREADMUTEXOBJECT_H_ */ ================================================ FILE: obj_pose_est/mapping/build.sh ================================================ #!/bin/bash mkdir deps &> /dev/null cd deps #Add necessary extra repos version=$(lsb_release -a 2>&1) if [[ $version == *"14.04"* ]] ; then wget http://developer.download.nvidia.com/compute/cuda/repos/ubuntu1404/x86_64/cuda-repo-ubuntu1404_7.5-18_amd64.deb sudo dpkg -i cuda-repo-ubuntu1404_7.5-18_amd64.deb rm cuda-repo-ubuntu1404_7.5-18_amd64.deb sudo apt-get update sudo apt-get install cuda-7-5 elif [[ $version == *"15.04"* ]] ; then wget http://developer.download.nvidia.com/compute/cuda/repos/ubuntu1504/x86_64/cuda-repo-ubuntu1504_7.5-18_amd64.deb sudo dpkg -i cuda-repo-ubuntu1504_7.5-18_amd64.deb rm cuda-repo-ubuntu1504_7.5-18_amd64.deb sudo apt-get update sudo apt-get install cuda-7-5 elif [[ $version == *"16.04"* ]] ; then wget http://developer.download.nvidia.com/compute/cuda/repos/ubuntu1604/x86_64/cuda-repo-ubuntu1604_8.0.44-1_amd64.deb sudo dpkg -i cuda-repo-ubuntu1604_8.0.44-1_amd64.deb rm cuda-repo-ubuntu1604_8.0.44-1_amd64.deb sudo add-apt-repository ppa:openjdk-r/ppa sudo apt-get update sudo apt-get install cuda-8-0 else echo "Don't use this on anything except 14.04, 15.04, or 16.04" exit fi sudo apt-get install -y cmake-qt-gui git build-essential libusb-1.0-0-dev libudev-dev openjdk-7-jdk freeglut3-dev libglew-dev libsuitesparse-dev libeigen3-dev zlib1g-dev libjpeg-dev #Installing Pangolin git clone https://github.com/stevenlovegrove/Pangolin.git cd Pangolin mkdir build cd build cmake ../ -DAVFORMAT_INCLUDE_DIR="" -DCPP11_NO_BOOST=ON make -j8 cd ../.. #Up to date OpenNI2 git clone https://github.com/occipital/OpenNI2.git cd OpenNI2 make -j8 cd .. #Actually build ElasticFusion cd ../Core mkdir build cd build cmake ../src make -j8 cd ../../GPUTest mkdir build cd build cmake ../src make -j8 cd ../../GUI mkdir build cd build cmake ../src make -j8 ================================================ FILE: obj_pose_est/package.xml ================================================ obj_pose_est 0.0.0 The obj_pose_est package hoang TODO catkin cv_bridge pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs std_srvs visualization_msgs message_generation cv_bridge pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs std_srvs visualization_msgs message_generation cv_bridge pcl_conversions pcl_ros roscpp rospy sensor_msgs std_msgs std_srvs visualization_msgs message_runtime ================================================ FILE: obj_pose_est/scripts/ObjectRPE_srv.py ================================================ #!/usr/bin/env python from obj_pose_est.srv import * import rospy import os def handle_ObjectRPE(req): mask_dir = req.data_dir + '/mask/*' mask_color_dir = req.data_dir + '/mask-color/*' os.system('rm -r ' + mask_dir) os.system('rm -r ' + mask_color_dir) #--------------------------Start DenseFusion--------------------------- print "Mask-RCNN running ..." executed_file = os.path.join(req.ObjectRPE_dir, 'Mask_RCNN/samples/warehouse/iliad.py') maskrcnn_model_dir = ' --weights=' + os.path.join(req.data_dir, 'trained_models/warehouse/mask_rcnn.h5') num_frames = ' --num_frames=' + str(req.num_frames) num_keyframes = ' --num_keyframes=' + str(req.num_keyframes) data_dir = ' --data=' + req.data_dir aa = os.popen('python3 ' + executed_file + maskrcnn_model_dir + data_dir + num_frames + num_keyframes).read() #--------------------------End DenseFusion--------------------------- print "3D mapping running ..." executed_file = os.path.join(req.ObjectRPE_dir, 'obj_pose_est/mapping/app/build/mapping') data_dir = ' -l ' + req.data_dir + '/' num_frames = ' -num_frames ' + str(req.num_frames) aa = os.popen(executed_file + data_dir + num_frames).read() #--------------------------Start DenseFusion--------------------------- print("DenseFusion running ...") densefusion_dir = req.ObjectRPE_dir + '/DenseFusion' executed_file = ' ./tools/iliad.py' dataset_root = ' --dataset_root ' + req.data_dir + '/dataset/warehouse' saved_root = ' --saved_root ' + req.data_dir pose_model = ' --model ' + os.path.join(req.data_dir, 'trained_models/warehouse/pose_model.pth') pose_refine_model = ' --refine_model ' + os.path.join(req.data_dir, 'trained_models/warehouse/pose_refine_model.pth') num_frames = ' --num_frames ' + str(req.num_frames) num_keyframes = ' --num_keyframes=' + str(req.num_keyframes) os.chdir(densefusion_dir) aa = os.popen('python3' + executed_file + dataset_root + saved_root + pose_model + pose_refine_model + num_frames + num_keyframes).read() #--------------------------End DenseFusion--------------------------- return 1; def ObjectRPE_server(): rospy.init_node('ObjectRPE_server') s = rospy.Service('Seg_Reconst_PoseEst', ObjectRPE, handle_ObjectRPE) print "Ready to run ObjectRPE." rospy.spin() if __name__ == "__main__": print('The current working directory:') print(os.getcwd()) ObjectRPE_server() ================================================ FILE: obj_pose_est/src/iliad_rpe_cam_node.cpp ================================================ #include #include #include #include #include #include #include #include #include #include #include "obj_pose_est/model_to_scene.h" #include "obj_pose_est/ObjectRPE.h" using namespace cv; using namespace std; class rpeCamNode { public: rpeCamNode(); virtual ~rpeCamNode(); void subcribeTopics(); void advertiseTopics(); void depthCallback(const sensor_msgs::Image::ConstPtr& msg); void rgbCallback(const sensor_msgs::Image::ConstPtr& msg); // Process object poses double overlapPortion(const pcl::PointCloud &source, const pcl::PointCloud &target, const double &max_dist); bool depthToClould(); void colorMap(int i, pcl::PointXYZRGB &point); void extract_cam_pose(std::string line); void processModels(); void getCalibrationParas(std::string dataset); void extract_transform_from_quaternion(std::string line, Eigen::Matrix4f &T, int class_index); void pose_process(); // Save data bool only_save_frames, call_service; int depth_now, rgb_now; int num_frames, num_keyframes; std::string data_dir, dataset, ObjectRPE_dir; std::string depth_topsub, rgb_topsub; std::string saved_rgb_dir, saved_depth_dir; // Process object poses pcl::PointCloud::Ptr scene_cloud, transformed_scene; pcl::PointCloud::Ptr pub_cloud; std::string depth_path, rgb_path; cv::Mat rgb_img, depth_img; double fx, fy, cx, cy, depth_factor; double dst_thresh; // minimum distance between two points considered as overlapped double overlap_thresh; // minimum overlap portion between two poinclouds considered as the same instance double confidence_thresh; // minimum confidence score of pose estimation for picking std::vector model_paths; // path to model of object detected std::vector full_items; // full list of item names in dataset std::vector transforms; Eigen::Matrix4f cam_T; // Multi prediction process std::vector> curr_models; std::vector curr_objects; // names of object detected in the current image std::vector curr_clsIDs; // class ID of object detected in the current image std::vector> global_models; std::vector global_objects; // names of object detected in the current image std::vector global_clsIDs; // class ID of object detected in the current image std::vector global_transforms; std::vector confidence_scores; private: ros::NodeHandle nh_, nh_rgb, nh_depth, nh_cloud, nh_srv; ros::Subscriber depth_sub, rgb_sub; ros::Publisher cloud_pub; ros::ServiceClient client; obj_pose_est::ObjectRPE srv; }; rpeCamNode::rpeCamNode() { nh_ = ros::NodeHandle("~"); nh_rgb = ros::NodeHandle("~"); nh_depth = ros::NodeHandle("~"); nh_cloud = ros::NodeHandle("~"); nh_depth.getParam("depth_topsub", depth_topsub); nh_rgb.getParam("rgb_topsub", rgb_topsub); nh_.getParam("only_save_frames", only_save_frames); nh_.getParam("ObjectRPE_dir", ObjectRPE_dir); nh_.getParam("dataset", dataset); nh_.getParam("data_dir", data_dir); nh_.getParam("num_frames", num_frames); nh_.getParam("num_keyframes", num_keyframes); nh_.getParam("call_service", call_service); nh_.getParam("dst_thresh", dst_thresh); nh_.getParam("overlap_thresh", overlap_thresh); nh_.getParam("confidence_thresh", confidence_thresh); client = nh_srv.serviceClient("Seg_Reconst_PoseEst"); srv.request.ObjectRPE_dir = ObjectRPE_dir; srv.request.dataset = dataset; srv.request.data_dir = data_dir; srv.request.num_frames = num_frames; srv.request.num_keyframes = num_keyframes; scene_cloud.reset(new pcl::PointCloud); transformed_scene.reset(new pcl::PointCloud); pub_cloud.reset(new pcl::PointCloud); depth_now = 0; rgb_now = 0; if(num_keyframes > num_frames) std::cerr << "The number of keyframes cannot larger than the number of frames!"; getCalibrationParas(dataset); } rpeCamNode::~rpeCamNode() { }; void rpeCamNode::subcribeTopics() { depth_sub = nh_depth.subscribe (depth_topsub, 1, &rpeCamNode::depthCallback, this); rgb_sub = nh_rgb.subscribe (rgb_topsub, 1, &rpeCamNode::rgbCallback, this); } void rpeCamNode::advertiseTopics() { cloud_pub = nh_cloud.advertise ("myCloud", 1); } void rpeCamNode::depthCallback (const sensor_msgs::Image::ConstPtr& msg) { cv_bridge::CvImageConstPtr bridge; try { bridge = cv_bridge::toCvCopy(msg, "32FC1"); } catch (cv_bridge::Exception& e) { ROS_ERROR("Failed to transform depth image."); return; } if(depth_now < num_frames & depth_now == rgb_now) { cv::Mat depth = bridge->image; depth.convertTo(depth, CV_16UC1, 1000.0); int now = 1000001 + depth_now; saved_depth_dir = data_dir + "/depth/" + std::to_string(now).substr(1, 6) + "-depth.png"; std::cerr << "Save " << saved_depth_dir << "\n"; cv::imwrite( saved_depth_dir, depth ); depth_now++; } if(only_save_frames) return; if(depth_now==num_frames & rgb_now==num_frames) { //-----------------------Call service for MaskRCNN and DenseFusion--------------------------- ROS_INFO("ObjectRPE running"); if (client.call(srv)) { ROS_INFO("Result: %ld", (long int)srv.response.ouput); } else { ROS_ERROR("Failed to call service ObjectRPE"); } pose_process(); depth_now=0; rgb_now=0; } if(pub_cloud->size()) { pcl::PCLPointCloud2 cloud_filtered; sensor_msgs::PointCloud2 output; pub_cloud->header.frame_id = "camera_depth_optical_frame"; pcl::toPCLPointCloud2(*pub_cloud, cloud_filtered); pcl_conversions::fromPCL(cloud_filtered, output); cloud_pub.publish (output); } } void rpeCamNode::rgbCallback (const sensor_msgs::Image::ConstPtr& msg) { cv_bridge::CvImageConstPtr bridge; try { bridge = cv_bridge::toCvCopy(msg, "bgr8"); } catch (cv_bridge::Exception& e) { ROS_ERROR("Failed to transform rgb image."); return; } if(rgb_now < num_frames & rgb_now < depth_now) { cv::Mat rgb_image; rgb_image = bridge->image; int now = 1000001 + rgb_now; saved_rgb_dir = data_dir + "/rgb/" + std::to_string(now).substr(1, 6) + "-color.png"; std::cerr << "Save " << saved_rgb_dir << "\n"; cv::imwrite( saved_rgb_dir, rgb_image ); rgb_now++; //cv::imshow("RGB image", rgb_image); //cv::waitKey(3); } } void rpeCamNode::getCalibrationParas(std::string dataset) { if(dataset == "YCB-Video") { } if(dataset == "Warehouse") { fx=580.0; fy=580.0; cx=319.0; cy=237.0; depth_factor = 1000; } } void rpeCamNode::extract_transform_from_quaternion(std::string line, Eigen::Matrix4f &T, int class_index) { Eigen::Vector3f trans; float rot_quaternion[4]; vector st; boost::trim(line); boost::split(st, line, boost::is_any_of("\t\r "), boost::token_compress_on); trans(0) = std::stof(st[4]); trans(1) = std::stof(st[5]); trans(2) = std::stof(st[6]); //translaton rot_quaternion[0] = std::stof(st[0]); rot_quaternion[1] = std::stof(st[1]); //rotation rot_quaternion[2] = std::stof(st[2]); rot_quaternion[3] = std::stof(st[3]); //rotation Eigen::Quaternionf q(rot_quaternion[0], rot_quaternion[1], rot_quaternion[2], rot_quaternion[3]); //w x y z T.block(0, 3, 3, 1) = trans; T.block(0, 0, 3, 3) = q.normalized().toRotationMatrix(); } void rpeCamNode::extract_cam_pose(std::string line) { Eigen::Vector3f trans; float rot_quaternion[4]; vector st; boost::trim(line); boost::split(st, line, boost::is_any_of("\t\r "), boost::token_compress_on); trans(0) = std::stof(st[1]); trans(1) = std::stof(st[2]); trans(2) = std::stof(st[3]); //translaton rot_quaternion[0] = std::stof(st[7]); rot_quaternion[1] = std::stof(st[4]); //rotation rot_quaternion[2] = std::stof(st[5]); rot_quaternion[3] = std::stof(st[6]); //rotation Eigen::Quaternionf q(rot_quaternion[0], rot_quaternion[1], rot_quaternion[2], rot_quaternion[3]); //w x y z cam_T.setIdentity(); cam_T.block(0, 3, 3, 1) = trans; cam_T.block(0, 0, 3, 3) = q.normalized().toRotationMatrix(); } bool rpeCamNode::depthToClould() { depth_img = cv::imread(depth_path, -1); rgb_img = cv::imread(rgb_path, -1); if(!rgb_img.data || !depth_img.data) { if(!rgb_img.data) std::cerr << "Cannot read image from " << rgb_path << "\n"; else std::cerr << "Cannot read image from " << depth_path << "\n"; return false; } cv::imshow("rgb", rgb_img); cv::waitKey(300); scene_cloud.reset(new pcl::PointCloud); pcl::PointXYZRGB point; for(int row=0; row < depth_img.rows; row++) { for(int col=0; col < depth_img.cols; col++) { if(isnan(depth_img.at(row, col))) continue; double depth = depth_img.at(row, col) / depth_factor; point.x = (col-cx) * depth / fx; point.y = (row-cy) * depth / fy; point.z = depth; point.b = rgb_img.at(row, col)[0]; point.g = rgb_img.at(row, col)[1]; point.r = rgb_img.at(row, col)[2]; scene_cloud->push_back(point); } } return true; } void rpeCamNode::colorMap(int i, pcl::PointXYZRGB &point) { if (i == 1) // red { point.r = 255; point.g = 0; point.b = 0; } else if (i == 2) //line { point.r = 0; point.g = 255; point.b = 0; } else if ( i == 3) //blue { point.r = 0; point.g = 0; point.b = 255; } else if ( i == 4) //maroon { point.r = 128; point.g = 0; point.b = 0; } else if ( i == 5) //green { point.r = 0; point.g = 128; point.b = 0; } else if ( i == 6) //navy { point.r = 0; point.g = 0; point.b = 128; } else if ( i == 7) //yellow { point.r = 255; point.g = 255; point.b = 0; } else if ( i == 8) //magenta { point.r = 255; point.g = 0; point.b = 255; } else if ( i == 9) //cyan { point.r = 0; point.g = 255; point.b = 255; } else if ( i == 10) //olive { point.r = 128; point.g = 128; point.b = 0; } else if ( i == 11) //purple { point.r = 128; point.g = 0; point.b = 128; } else if ( i == 12) //teal { point.r = 0; point.g = 128; point.b = 128; } else if ( i == 13) { point.r = 92; point.g = 112; point.b = 92; } else if ( i == 14) //brown { point.r = 165; point.g = 42; point.b = 42; } else //silver { point.r = 192; point.g = 192; point.b = 192; } } double rpeCamNode::overlapPortion(const pcl::PointCloud &source, const pcl::PointCloud &target, const double &max_dist) { if (source.size() == 0 || target.size() == 0) return -1; pcl::PointCloud::Ptr target_cloud(new pcl::PointCloud); pcl::PointCloud::Ptr source_cloud(new pcl::PointCloud); pcl::copyPointCloud(target, *target_cloud); pcl::copyPointCloud(source, *source_cloud); pcl::KdTreeFLANN kdtree; kdtree.setInputCloud(target_cloud); std::vector pointIdxNKNSearch(1); std::vector pointNKNSquaredDistance(1); int overlap_Points = 0; for (int i = 0; i < source.size(); ++i) { if (kdtree.nearestKSearch(source_cloud->points[i], 1, pointIdxNKNSearch, pointNKNSquaredDistance) > 0) { if(sqrt(pointNKNSquaredDistance[0]) < max_dist) overlap_Points++; } } //calculating the mean distance double portion = (double) overlap_Points / source.size(); return portion; } void rpeCamNode::processModels() { pcl::PointCloud::Ptr model_cloud (new pcl::PointCloud); std::vector> original_models; pcl::PointCloud::Ptr color_model_cloud (new pcl::PointCloud); for(int i=0; i < model_paths.size(); i++) { pcl::io::loadPLYFile (model_paths[i], *model_cloud); copyPointCloud(*model_cloud, *color_model_cloud); original_models.push_back(*color_model_cloud); pcl::transformPointCloud(*color_model_cloud, *color_model_cloud, transforms[i]); for(int k=0; k < color_model_cloud->size(); k++) { colorMap(i+1, color_model_cloud->points[k]); } curr_models.push_back(*color_model_cloud); } if(!curr_models.size()) return; if(!global_models.size()) { for(int i=0; i < curr_models.size(); i++) { pcl::PointCloud::Ptr transformed_model (new pcl::PointCloud); pcl::transformPointCloud(curr_models[i], *transformed_model, cam_T); global_models.push_back(*transformed_model); global_objects.push_back(curr_objects[i]); global_clsIDs.push_back(curr_clsIDs[i]); confidence_scores.push_back(1); Eigen::Matrix4f global_T = cam_T * transforms[i]; global_transforms.push_back(global_T); } return; } for(int i=0; i < curr_models.size(); i++) { pcl::PointCloud::Ptr transformed_model (new pcl::PointCloud); pcl::transformPointCloud(curr_models[i], *transformed_model, cam_T); int numOfGlobalObjects = global_models.size(); bool new_object = true; for(int j=0; j < numOfGlobalObjects; j++) { if(curr_clsIDs[i] == global_clsIDs[j]) { double overlap = overlapPortion(*transformed_model, global_models[i], dst_thresh); if(overlap > overlap_thresh) { Eigen::Matrix4f global_T = cam_T * transforms[i]; global_T = (global_transforms[j] * confidence_scores[i] + global_T) / (confidence_scores[i]+1); pcl::transformPointCloud(original_models[i], *transformed_model, global_T); for(int k=0; k < transformed_model->size(); k++) { colorMap(j+1, transformed_model->points[k]); } global_models[j] = *transformed_model; confidence_scores[j] = confidence_scores[i] * (1+overlap); } new_object = false; } } if(new_object) { for(int k=0; k < transformed_model->size(); k++) { colorMap(global_models.size()+1, transformed_model->points[k]); } global_models.push_back(*transformed_model); global_clsIDs.push_back(curr_clsIDs[i]); global_objects.push_back(curr_objects[i]); confidence_scores.push_back(1); Eigen::Matrix4f global_T = cam_T * transforms[i]; global_transforms.push_back(global_T); } } } void rpeCamNode::pose_process() { std::string classes_path = data_dir + "/dataset/warehouse/image_sets/classes.txt"; std::string model_dir = data_dir + "/dataset/warehouse/models"; pcl::PCLPointCloud2 cloud_filtered; sensor_msgs::PointCloud2 output; ifstream classes_file (classes_path); if (classes_file.is_open()) { while (!classes_file.eof()) { string cls; getline (classes_file, cls); full_items.push_back(cls); } } else { std::cerr << "Unable to open " << classes_path << " file" << "\n"; exit(0); } classes_file.close(); std::string cam_traject_path = data_dir + "/map.freiburg"; ifstream cam_traject_file (cam_traject_path); if(cam_traject_file.fail()) { std::cerr << "Cannot read " << cam_traject_path << "n"; return; } cam_traject_file.clear(); cam_traject_file.seekg(0, ios::beg); global_models.clear(); global_objects.clear(); global_clsIDs.clear(); confidence_scores.clear(); global_transforms.clear(); for(int now=0; now < num_frames; now++) { string cam_line; if(!cam_traject_file.eof()) getline (cam_traject_file, cam_line); int num = 1000001 + now; std::string str_num = std::to_string(num).substr(1, 6); std::string pose_path = data_dir + "/mask/" + str_num + "-object_poses.txt"; ifstream posefile (pose_path); if(posefile.fail()) continue; pub_cloud.reset(new pcl::PointCloud); scene_cloud.reset(new pcl::PointCloud); transformed_scene.reset(new pcl::PointCloud); model_paths.clear(); transforms.clear(); curr_objects.clear(); curr_clsIDs.clear(); curr_models.clear(); depth_path = data_dir + "/depth/" + str_num + "-depth.png"; rgb_path = data_dir + "/rgb/" + str_num + "-color.png"; string line; if (posefile.is_open()) { while(!posefile.eof()) { if(!posefile.eof()) getline (posefile, line); if(line=="") continue; curr_clsIDs.push_back(std::stoi(line)); int cls_index = std::stoi(line) - 1; std::string model_path = model_dir + "/" + full_items[cls_index] + "/points.ply"; curr_objects.push_back(full_items[cls_index]); model_paths.push_back(model_path); if(!posefile.eof()) getline (posefile, line); if(line=="") continue; Eigen::Matrix4f T(Eigen::Matrix4f::Identity()); extract_transform_from_quaternion(line, T, cls_index); transforms.push_back(T); } } else { std::cerr << "Unable to open file"; exit(0); } if(model_paths.size()) { if(!depthToClould()) continue ; if(cam_line!="") { extract_cam_pose(cam_line); pcl::transformPointCloud(*scene_cloud, *transformed_scene, cam_T); } else continue; processModels(); } if(cam_line!="") { extract_cam_pose(cam_line); pcl::transformPointCloud(*scene_cloud, *transformed_scene, cam_T); } posefile.close(); } cam_traject_file.close(); pub_cloud.reset(new pcl::PointCloud); *pub_cloud += *transformed_scene; pub_cloud->header.frame_id = "camera_depth_optical_frame"; if(global_models.size()) { for(int i=0; i < global_models.size(); i++) { if(confidence_scores[i] > confidence_thresh) *pub_cloud += global_models[i]; } } } int main(int argc, char** argv) { ros::init(argc, argv, "find_transform"); rpeCamNode mainNode; mainNode.subcribeTopics(); mainNode.advertiseTopics(); ros::spin(); return 0; } ================================================ FILE: obj_pose_est/src/iliad_rpe_node.cpp ================================================ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "obj_pose_est/model_to_scene.h" #include "obj_pose_est/ObjectRPE.h" using namespace std; using namespace cv; pcl::PointCloud::Ptr scene_cloud (new pcl::PointCloud); pcl::PointCloud::Ptr transformed_scene (new pcl::PointCloud); pcl::PointCloud::Ptr pub_one_pred (new pcl::PointCloud); pcl::PointCloud::Ptr pub_multi_pred (new pcl::PointCloud); std::string depth_path, rgb_path; cv::Mat rgb_img, depth_img; double fx, fy, cx, cy, depth_factor; double dst_thresh; // minimum distance between two points considered as overlapped double overlap_thresh; // minimum overlap portion between two poinclouds considered as the same instance double confidence_thresh; // minimum confidence score of pose estimation for picking std::vector model_paths; // path to model of object detected std::vector full_items; // full list of item names in dataset std::vector transforms; Eigen::Matrix4f cam_T; std::vector> curr_models; std::vector curr_objects; // names of object detected in the current image std::vector curr_clsIDs; // class ID of object detected in the current image std::vector> global_models; std::vector global_objects; // names of object detected in the current image std::vector global_clsIDs; // class ID of object detected in the current image std::vector global_transforms; std::vector confidence_scores; bool depthToClould() { depth_img = cv::imread(depth_path, -1); rgb_img = cv::imread(rgb_path, -1); if(!rgb_img.data || !depth_img.data) { if(!rgb_img.data) std::cerr << "Cannot read image from " << rgb_path << "\n"; else std::cerr << "Cannot read image from " << depth_path << "\n"; return false; } cv::imshow("rgb", rgb_img); cv::waitKey(300); scene_cloud.reset(new pcl::PointCloud); pcl::PointXYZRGB point; for(int row=0; row < depth_img.rows; row++) { for(int col=0; col < depth_img.cols; col++) { if(isnan(depth_img.at(row, col))) continue; double depth = depth_img.at(row, col) / depth_factor; point.x = (col-cx) * depth / fx; point.y = (row-cy) * depth / fy; point.z = depth; point.b = rgb_img.at(row, col)[0]; point.g = rgb_img.at(row, col)[1]; point.r = rgb_img.at(row, col)[2]; scene_cloud->push_back(point); } } return true; } void colorMap(int i, pcl::PointXYZRGB &point) { if (i == 1) // red { point.r = 255; point.g = 0; point.b = 0; } else if (i == 2) //line { point.r = 0; point.g = 255; point.b = 0; } else if ( i == 3) //blue { point.r = 0; point.g = 0; point.b = 255; } else if ( i == 4) //maroon { point.r = 128; point.g = 0; point.b = 0; } else if ( i == 5) //green { point.r = 0; point.g = 128; point.b = 0; } else if ( i == 6) //navy { point.r = 0; point.g = 0; point.b = 128; } else if ( i == 7) //yellow { point.r = 255; point.g = 255; point.b = 0; } else if ( i == 8) //magenta { point.r = 255; point.g = 0; point.b = 255; } else if ( i == 9) //cyan { point.r = 0; point.g = 255; point.b = 255; } else if ( i == 10) //olive { point.r = 128; point.g = 128; point.b = 0; } else if ( i == 11) //purple { point.r = 128; point.g = 0; point.b = 128; } else if ( i == 12) //teal { point.r = 0; point.g = 128; point.b = 128; } else if ( i == 13) { point.r = 92; point.g = 112; point.b = 92; } else if ( i == 14) //brown { point.r = 165; point.g = 42; point.b = 42; } else //silver { point.r = 192; point.g = 192; point.b = 192; } } double overlapPortion(const pcl::PointCloud &source, const pcl::PointCloud &target, const double &max_dist) { if (source.size() == 0 || target.size() == 0) return -1; pcl::PointCloud::Ptr target_cloud(new pcl::PointCloud); pcl::PointCloud::Ptr source_cloud(new pcl::PointCloud); pcl::copyPointCloud(target, *target_cloud); pcl::copyPointCloud(source, *source_cloud); pcl::KdTreeFLANN kdtree; kdtree.setInputCloud(target_cloud); std::vector pointIdxNKNSearch(1); std::vector pointNKNSquaredDistance(1); int overlap_Points = 0; for (int i = 0; i < source.size(); ++i) { if (kdtree.nearestKSearch(source_cloud->points[i], 1, pointIdxNKNSearch, pointNKNSquaredDistance) > 0) { if(sqrt(pointNKNSquaredDistance[0]) < max_dist) overlap_Points++; } } //calculating the mean distance double portion = (double) overlap_Points / source.size(); return portion; } void processModels() { pcl::PointCloud::Ptr model_cloud (new pcl::PointCloud); std::vector> original_models; pcl::PointCloud::Ptr color_model_cloud (new pcl::PointCloud); for(int i=0; i < model_paths.size(); i++) { pcl::io::loadPLYFile (model_paths[i], *model_cloud); copyPointCloud(*model_cloud, *color_model_cloud); original_models.push_back(*color_model_cloud); pcl::transformPointCloud(*color_model_cloud, *color_model_cloud, transforms[i]); for(int k=0; k < color_model_cloud->size(); k++) { colorMap(i+1, color_model_cloud->points[k]); } curr_models.push_back(*color_model_cloud); } if(!curr_models.size()) return; if(!global_models.size()) { for(int i=0; i < curr_models.size(); i++) { pcl::PointCloud::Ptr transformed_model (new pcl::PointCloud); pcl::transformPointCloud(curr_models[i], *transformed_model, cam_T); global_models.push_back(*transformed_model); global_objects.push_back(curr_objects[i]); global_clsIDs.push_back(curr_clsIDs[i]); confidence_scores.push_back(1); Eigen::Matrix4f global_T = cam_T * transforms[i]; global_transforms.push_back(global_T); } return; } for(int i=0; i < curr_models.size(); i++) { pcl::PointCloud::Ptr transformed_model (new pcl::PointCloud); pcl::transformPointCloud(curr_models[i], *transformed_model, cam_T); int numOfGlobalObjects = global_models.size(); bool new_object = true; for(int j=0; j < numOfGlobalObjects; j++) { if(curr_clsIDs[i] == global_clsIDs[j]) { double overlap = overlapPortion(*transformed_model, global_models[i], dst_thresh); if(overlap > overlap_thresh) { Eigen::Matrix4f global_T = cam_T * transforms[i]; global_T = (global_transforms[j] * confidence_scores[i] + global_T) / (confidence_scores[i]+1); pcl::transformPointCloud(original_models[i], *transformed_model, global_T); for(int k=0; k < transformed_model->size(); k++) { colorMap(j+1, transformed_model->points[k]); } global_models[j] = *transformed_model; confidence_scores[j] = confidence_scores[i] * (1+overlap); } new_object = false; } } if(new_object) { for(int k=0; k < transformed_model->size(); k++) { colorMap(global_models.size()+1, transformed_model->points[k]); } global_models.push_back(*transformed_model); global_clsIDs.push_back(curr_clsIDs[i]); global_objects.push_back(curr_objects[i]); confidence_scores.push_back(1); Eigen::Matrix4f global_T = cam_T * transforms[i]; global_transforms.push_back(global_T); } } } void getCalibrationParas(std::string dataset) { if(dataset == "YCB-Video") { } if(dataset == "Warehouse") { fx=580.0; fy=580.0; cx=319.0; cy=237.0; depth_factor = 1000; } } void extract_transform_from_quaternion(std::string line, Eigen::Matrix4f &T, int class_index) { Eigen::Vector3f trans; float rot_quaternion[4]; vector st; boost::trim(line); boost::split(st, line, boost::is_any_of("\t\r "), boost::token_compress_on); trans(0) = std::stof(st[4]); trans(1) = std::stof(st[5]); trans(2) = std::stof(st[6]); //translaton rot_quaternion[0] = std::stof(st[0]); rot_quaternion[1] = std::stof(st[1]); //rotation rot_quaternion[2] = std::stof(st[2]); rot_quaternion[3] = std::stof(st[3]); //rotation Eigen::Quaternionf q(rot_quaternion[0], rot_quaternion[1], rot_quaternion[2], rot_quaternion[3]); //w x y z T.block(0, 3, 3, 1) = trans; T.block(0, 0, 3, 3) = q.normalized().toRotationMatrix(); } void extract_cam_pose(std::string line) { Eigen::Vector3f trans; float rot_quaternion[4]; vector st; boost::trim(line); boost::split(st, line, boost::is_any_of("\t\r "), boost::token_compress_on); trans(0) = std::stof(st[1]); trans(1) = std::stof(st[2]); trans(2) = std::stof(st[3]); //translaton rot_quaternion[0] = std::stof(st[7]); rot_quaternion[1] = std::stof(st[4]); //rotation rot_quaternion[2] = std::stof(st[5]); rot_quaternion[3] = std::stof(st[6]); //rotation Eigen::Quaternionf q(rot_quaternion[0], rot_quaternion[1], rot_quaternion[2], rot_quaternion[3]); //w x y z cam_T.setIdentity(); cam_T.block(0, 3, 3, 1) = trans; cam_T.block(0, 0, 3, 3) = q.normalized().toRotationMatrix(); } int main(int argc, char** argv) { ros::init(argc, argv, "ObjectRPE"); ros::NodeHandle nh_, nh_srv, nh_cloud, cloud_mul_n; ros::Publisher cloud_pub_one_pred = nh_cloud.advertise ("one_pred", 1); ros::Publisher cloud_pub_multi_pred = cloud_mul_n.advertise ("multi_pred", 1); ros::Rate loop_rate(10); std::string dataset, ObjectRPE_dir, data_dir; int num_frames, num_keyframes; bool call_service; nh_ = ros::NodeHandle("~"); nh_.getParam("ObjectRPE_dir", ObjectRPE_dir); nh_.getParam("dataset", dataset); nh_.getParam("data_dir", data_dir); nh_.getParam("num_frames", num_frames); nh_.getParam("num_keyframes", num_keyframes); nh_.getParam("call_service", call_service); nh_.getParam("dst_thresh", dst_thresh); nh_.getParam("overlap_thresh", overlap_thresh); nh_.getParam("confidence_thresh", confidence_thresh); if(num_keyframes > num_frames) std::cerr << "The number of keyframes cannot larger than the number of frames!"; getCalibrationParas(dataset); //-----------------------Call service for MaskRCNN and DenseFusion--------------------------- if(call_service) { ros::ServiceClient client = nh_srv.serviceClient("Seg_Reconst_PoseEst"); obj_pose_est::ObjectRPE srv; srv.request.ObjectRPE_dir = ObjectRPE_dir; srv.request.dataset = dataset; srv.request.data_dir = data_dir; srv.request.num_frames = num_frames; srv.request.num_keyframes = num_keyframes; ROS_INFO("ObjectRPE running"); if (client.call(srv)) { ROS_INFO("Result: %ld", (long int)srv.response.ouput); } else { ROS_ERROR("Failed to call service ObjectRPE"); return 1; } } //-----------------------------------Process predictions------------------------------------- std::string classes_path = data_dir + "/dataset/warehouse/image_sets/classes.txt"; std::string model_dir = data_dir + "/dataset/warehouse/models"; pcl::PCLPointCloud2 cloud_filtered; sensor_msgs::PointCloud2 output; ifstream classes_file (classes_path); if (classes_file.is_open()) { while (!classes_file.eof()) { string cls; getline (classes_file, cls); full_items.push_back(cls); } } else { std::cerr << "Unable to open " << classes_path << " file" << "\n"; exit(0); } classes_file.close(); std::string cam_traject_path = data_dir + "/map.freiburg"; ifstream cam_traject_file (cam_traject_path); if(cam_traject_file.fail()) { std::cerr << "Cannot read " << cam_traject_path << "n"; return 1; } int now = 0; while (ros::ok()) { if(now < num_frames) now++; else { now = 0; pub_multi_pred.reset(new pcl::PointCloud); cam_traject_file.clear(); cam_traject_file.seekg(0, ios::beg); global_models.clear(); global_objects.clear(); global_clsIDs.clear(); confidence_scores.clear(); global_transforms.clear(); continue; } string cam_line; if(!cam_traject_file.eof()) getline (cam_traject_file, cam_line); int num = 1000000 + now; std::string str_num = std::to_string(num).substr(1, 6); std::string pose_path = data_dir + "/mask/" + str_num + "-object_poses.txt"; ifstream posefile (pose_path); if(posefile.fail()) continue; pub_one_pred.reset(new pcl::PointCloud); pub_multi_pred.reset(new pcl::PointCloud); scene_cloud.reset(new pcl::PointCloud); transformed_scene.reset(new pcl::PointCloud); model_paths.clear(); transforms.clear(); curr_objects.clear(); curr_clsIDs.clear(); curr_models.clear(); depth_path = data_dir + "/depth/" + str_num + "-depth.png"; rgb_path = data_dir + "/rgb/" + str_num + "-color.png"; string line; if (posefile.is_open()) { while(!posefile.eof()) { if(!posefile.eof()) getline (posefile, line); if(line=="") continue; curr_clsIDs.push_back(std::stoi(line)); int cls_index = std::stoi(line) - 1; std::string model_path = model_dir + "/" + full_items[cls_index] + "/points.ply"; curr_objects.push_back(full_items[cls_index]); model_paths.push_back(model_path); if(!posefile.eof()) getline (posefile, line); if(line=="") continue; Eigen::Matrix4f T(Eigen::Matrix4f::Identity()); extract_transform_from_quaternion(line, T, cls_index); transforms.push_back(T); } } else { std::cerr << "Unable to open file"; exit(0); } if(model_paths.size()) { if(!depthToClould()) continue ; if(cam_line!="") { extract_cam_pose(cam_line); pcl::transformPointCloud(*scene_cloud, *transformed_scene, cam_T); } else continue; processModels(); } if(cam_line!="") { extract_cam_pose(cam_line); pcl::transformPointCloud(*scene_cloud, *transformed_scene, cam_T); } if(curr_models.size()) { for(int i=0; i < curr_models.size(); i++) *pub_one_pred += curr_models[i]; } if(global_models.size()) { for(int i=0; i < global_models.size(); i++) { if(confidence_scores[i] > confidence_thresh) *pub_multi_pred += global_models[i]; } } *pub_one_pred += *scene_cloud; pub_one_pred->header.frame_id = "camera_depth_optical_frame"; *pub_multi_pred += *transformed_scene; pub_multi_pred->header.frame_id = "camera_depth_optical_frame"; pcl::toPCLPointCloud2(*pub_one_pred, cloud_filtered); pcl_conversions::fromPCL(cloud_filtered, output); cloud_pub_one_pred.publish (output); pcl::toPCLPointCloud2(*pub_multi_pred, cloud_filtered); pcl_conversions::fromPCL(cloud_filtered, output); cloud_pub_multi_pred.publish (output); ros::spinOnce(); loop_rate.sleep(); posefile.close(); } cam_traject_file.close(); return 0; } ================================================ FILE: obj_pose_est/src/kalman_filter.cpp ================================================ #include "obj_pose_est/kalman_filter.h" kalman_filter::kalman_filter() { std::cerr << "Start Kalman Filter!!!\n"; } kalman_filter::~kalman_filter() { } inline Vector6f kalman_filter::subPose(const Vector6f &origin, const Vector6f &pose) { Eigen::Affine3f origin_A = Eigen::Affine3f::Identity(); origin_A.translation() << origin(0), origin(1), origin(2); origin_A.rotate (Eigen::AngleAxisf (origin(3), Eigen::Vector3f::UnitX())); origin_A.rotate (Eigen::AngleAxisf (origin(4), Eigen::Vector3f::UnitY())); origin_A.rotate (Eigen::AngleAxisf (origin(5), Eigen::Vector3f::UnitZ())); Eigen::Affine3f pose_A = Eigen::Affine3f::Identity(); pose_A.translation() << pose(0), pose(1), pose(2); pose_A.rotate (Eigen::AngleAxisf (origin(3), Eigen::Vector3f::UnitX())); pose_A.rotate (Eigen::AngleAxisf (origin(4), Eigen::Vector3f::UnitY())); pose_A.rotate (Eigen::AngleAxisf (origin(5), Eigen::Vector3f::UnitZ())); Eigen::Affine3f result_A; result_A.matrix() = origin_A.matrix()*pose_A.matrix().inverse(); Vector3f rot = result_A.rotation().eulerAngles(0, 1, 2); Vector6f result; result(0) = result_A.translation()(0); result(1) = result_A.translation()(1); result(2) = result_A.translation()(2); result(3) = rot(0); result(4) = rot(1); result(5) = rot(3); return result; } inline Vector6f kalman_filter::addPose(const Vector6f &origin, const Vector6f &pose) { Eigen::Affine3f origin_A = Eigen::Affine3f::Identity(); origin_A.translation() << origin(0), origin(1), origin(2); origin_A.rotate (Eigen::AngleAxisf (origin(3), Eigen::Vector3f::UnitX())); origin_A.rotate (Eigen::AngleAxisf (origin(4), Eigen::Vector3f::UnitY())); origin_A.rotate (Eigen::AngleAxisf (origin(5), Eigen::Vector3f::UnitZ())); Eigen::Affine3f pose_A = Eigen::Affine3f::Identity(); pose_A.translation() << pose(0), pose(1), pose(2); pose_A.rotate (Eigen::AngleAxisf (origin(3), Eigen::Vector3f::UnitX())); pose_A.rotate (Eigen::AngleAxisf (origin(4), Eigen::Vector3f::UnitY())); pose_A.rotate (Eigen::AngleAxisf (origin(5), Eigen::Vector3f::UnitZ())); Eigen::Affine3f result_A; result_A.matrix() = origin_A.matrix()*pose_A.matrix(); Vector3f rot = result_A.rotation().eulerAngles(0, 1, 2); Vector6f result; result(0) = result_A.translation()(0); result(1) = result_A.translation()(1); result(2) = result_A.translation()(2); result(3) = rot(0); result(4) = rot(1); result(5) = rot(3); return result; } bool kalman_filter::Kalman_update(const Vector6f &measure_X, const Matrix6f &measure_cov, Vector6f &est_X, Matrix6f &est_cov) { Matrix6f Rk, Sk, Kk, Ik, Sk_inv; Ik.setIdentity(); Vector6f yk; Vector6f measured, estimated, residual, corrected, correction; measured(0) = measure_X(0); measured(1) = measure_X(1); measured(2) = measure_X(2); measured(3) = measure_X(3); measured(4) = measure_X(4); measured(5) = measure_X(5); estimated(0) = est_X(0); estimated(1) = est_X(1); estimated(2) = est_X(2); estimated(3) = est_X(3); estimated(4) = est_X(4); estimated(5) = est_X(5); bool invertible; double det; residual = subPose(estimated, measured); Rk = measure_cov; Sk = est_cov + Rk; FullPivLU lu_decomp(Sk); invertible = lu_decomp.isInvertible(); if (!invertible) { std::cerr << "Matrix not invertible \n"; } else { Sk_inv = Sk.inverse(); } yk(0) = residual(0); yk(1) = residual(1); yk(2) = residual(2); yk(3) = residual(3); yk(4) = residual(4); yk(5) = residual(5); Kk = est_cov*Sk_inv; yk = Kk*yk; correction(0) = yk(0); correction(1) = yk(1); correction(2) = yk(2); correction(3) = yk(3); correction(4) = yk(4); correction(5) = yk(5); corrected = addPose(estimated, correction); //est_X(0) = corrected(0); est_X(1) = corrected(1); est_X(2) = corrected(2); //est_X(3) = corrected(3); est_X(4) = corrected(4); est_X(5) = corrected(5); est_X = corrected; est_cov = (Ik - Kk)*est_cov; } ================================================ FILE: obj_pose_est/src/model_to_scene.cpp ================================================ #include "obj_pose_est/model_to_scene.h" model_to_scene::model_to_scene() { std::cerr << "Start model to scene!!!\n"; } model_to_scene::~model_to_scene() { } int model_to_scene::color_to_instanceID(unsigned char r, unsigned char g, unsigned char b) { if(r==128 & g==128 & b==0) return 1; else if(r==0 & g==128 & b==128) return 2; else if(r==128 & g==0 & b==128) return 3; else if(r==128 & g==0 & b==0) return 4; else if(r==0 & g==128 & b==0) return 5; else if(r==0 & g==0 & b==128) return 6; else if(r==255 & g==255 & b==0) return 7; else if(r==255 & g==0 & b==255) return 8; else if(r==0 & g==255 & b==255) return 9; else if(r==255 & g==0 & b==0) return 10; else if(r==0 & g==255 & b==0) return 11; else if(r==0 & g==0 & b==255) return 12; else if(r==92 & g==112 & b==92) return 13; else if(r==0 & g==0 & b==70) return 14; else if(r==0 & g==60 & b==100) return 15; else if(r==0 & g==80 & b==100) return 16; else if(r==0 & g==0 & b==230) return 17; else if(r==119 & g==11 & b==32) return 18; else if(r==0 & g==0 & b==121) return 19; else return 0; } void model_to_scene::cloud_to_instances(const pcl::PointCloud &input, std::vector &objects) { for(int i=0; i < input.size(); i++) { pcl::PointXYZRGB point; point = input.points[i]; int objID; if(point.r==192 & point.g==192 & point.b==192) continue; else objID = color_to_instanceID(point.r, point.g, point.b); if(!objID) continue; pcl::PointXYZ pointXYZ; pointXYZ.x=point.x; pointXYZ.y=point.y; pointXYZ.z=point.z; objects[objID-1].points.push_back(point); } } void model_to_scene::noiseRemoval(std::vector &objects) { for(int i=0 ; i < objects.size(); i++) { if(objects[i].points.size() == 0) continue; pcl::PointCloud::Ptr cloud (new pcl::PointCloud()); pcl::copyPointCloud(objects[i].points, *cloud); pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); std::vector cluster_indices; tree->setInputCloud(cloud); pcl::EuclideanClusterExtraction ec; ec.setClusterTolerance(0.02); ec.setMinClusterSize(500); ec.setMaxClusterSize(9999999); ec.setSearchMethod(tree); ec.setInputCloud(cloud); ec.extract(cluster_indices); objects[i].points.clear(); for (std::vector::const_iterator it = cluster_indices.begin(); it != cluster_indices.end(); ++it) { for (std::vector::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit) { objects[i].points.push_back(cloud->points[*pit]); } } } } void model_to_scene::load_models(const std::string model_dir, const std::string detected_class_ids_dir, const std::string class_list_dir, std::vector &models) { std::vector object_name_list; std::ifstream class_file(class_list_dir); std::string str; while (std::getline(class_file, str)) { object_name_list.push_back(str); } std::vector detected_object_ids; std::ifstream file(detected_class_ids_dir); while (std::getline(file, str)) { detected_object_ids.push_back(stoi(str)); } ObjectModel model; if(!models.empty()) models.clear(); for(int i=0 ; i < detected_object_ids.size(); i++) models.push_back(model); for(int i=0; i < models.size(); i++) { int class_id = detected_object_ids[i]; std::string model_path = model_dir + object_name_list[class_id-1] + "/points_view1.ply"; pcl::io::loadPLYFile (model_path, models[i].points_view); model_path = model_dir + object_name_list[class_id-1] + "/points.ply"; pcl::io::loadPLYFile (model_path, models[i].points_full); } } void model_to_scene::processCloud(const std::string cloud_path, const std::string detected_class_ids_path, const std::string class_list_path, const std::string model_dir) { load_models(model_dir, detected_class_ids_path, class_list_path, models); pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::io::loadPLYFile (cloud_path, *cloud); ObjectInstance instance; if(!instances.empty()) instances.clear(); for(int i=0 ; i < models.size(); i++) instances.push_back(instance); cloud_to_instances(*cloud, instances); noiseRemoval(instances); for (int i=0; i < instances.size(); i++) { pcl::PointCloud::Ptr source (new pcl::PointCloud); pcl::PointCloud::Ptr model (new pcl::PointCloud); pcl::PointCloud::Ptr target (new pcl::PointCloud); pcl::PointCloud::Ptr registed_source (new pcl::PointCloud); pcl::copyPointCloud(instances[i].points, *target); pcl::copyPointCloud(models[i].points_view, *source); pcl::copyPointCloud(models[i].points_full, *model); coarseToFineRegistration(*source, *model, *target, *registed_source); pcl::copyPointCloud(*registed_source, models[i].points_full); std::cerr << "Instance " << i << "\n" << "Registed!\n"; } std::cerr << "Object Poses Estimation Done!\n"; } void model_to_scene::computeOBB(const pcl::PointCloud &input, boundingBBox &OBB) { // Compute principal directions Eigen::Vector4f pcaCentroid; pcl::compute3DCentroid(input, pcaCentroid); Eigen::Matrix3f covariance; computeCovarianceMatrixNormalized(input, pcaCentroid, covariance); Eigen::SelfAdjointEigenSolver eigen_solver(covariance, Eigen::ComputeEigenvectors); Eigen::Matrix3f eigenVectorsPCA = eigen_solver.eigenvectors(); eigenVectorsPCA.col(2) = eigenVectorsPCA.col(0).cross(eigenVectorsPCA.col(1)); // Transform the original cloud to the origin where the principal components correspond to the axes. Eigen::Matrix4f projectionTransform(Eigen::Matrix4f::Identity()); projectionTransform.block<3,3>(0,0) = eigenVectorsPCA.transpose(); projectionTransform.block<3,1>(0,3) = -1.f * (projectionTransform.block<3,3>(0,0) * pcaCentroid.head<3>()); // Transform the original cloud to the origin where the principal components correspond to the axes. pcl::PointCloud::Ptr cloudPointsProjected (new pcl::PointCloud); pcl::transformPointCloud(input, *cloudPointsProjected, projectionTransform); // Get the minimum and maximum points of the transformed cloud. pcl::PointXYZ minPoint, maxPoint; pcl::getMinMax3D(*cloudPointsProjected, minPoint, maxPoint); OBB.length[0] = maxPoint.x - minPoint.x; //MAX length OBB OBB.length[1] = maxPoint.y - minPoint.y; //MID length OBB OBB.length[2] = maxPoint.z - minPoint.z; //MIN length OBB if(OBB.length[0] < OBB.length[1]) { float buf = OBB.length[0]; OBB.length[0] = OBB.length[1]; OBB.length[1] = buf; Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity(); transform_2.rotate (Eigen::AngleAxisf (M_PI/2.0, Eigen::Vector3f::UnitZ())); pcl::transformPointCloud (*cloudPointsProjected, *cloudPointsProjected, transform_2); projectionTransform = transform_2.matrix()*projectionTransform; } if(OBB.length[0] < OBB.length[2]) { float buf = OBB.length[0]; OBB.length[0] = OBB.length[2]; OBB.length[2] = buf; Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity(); transform_2.rotate (Eigen::AngleAxisf (M_PI/2.0, Eigen::Vector3f::UnitY())); pcl::transformPointCloud (*cloudPointsProjected, *cloudPointsProjected, transform_2); projectionTransform = transform_2.matrix()*projectionTransform; } if(OBB.length[1] < OBB.length[2]) { float buf = OBB.length[1]; OBB.length[1] = OBB.length[2]; OBB.length[2] = buf; Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity(); transform_2.rotate (Eigen::AngleAxisf (M_PI/2.0, Eigen::Vector3f::UnitX())); pcl::transformPointCloud (*cloudPointsProjected, *cloudPointsProjected, transform_2); projectionTransform = transform_2.matrix()*projectionTransform; } pcl::getMinMax3D(*cloudPointsProjected, OBB.minPoint, OBB.maxPoint); OBB.toOrigin = projectionTransform; pcl::PointXYZ OBB_points; OBB.cornerPoints.push_back(OBB.minPoint); // Min Point OBB_points.x = OBB.minPoint.x; OBB_points.y = OBB.maxPoint.y; OBB_points.z = OBB.minPoint.z; OBB.cornerPoints.push_back(OBB_points); OBB_points.x = OBB.minPoint.x; OBB_points.y = OBB.maxPoint.y; OBB_points.z = OBB.maxPoint.z; OBB.cornerPoints.push_back(OBB_points); OBB_points.x = OBB.minPoint.x; OBB_points.y = OBB.minPoint.y; OBB_points.z = OBB.maxPoint.z; OBB.cornerPoints.push_back(OBB_points); OBB.cornerPoints.push_back(OBB.maxPoint); //Max point OBB_points.x = OBB.maxPoint.x; OBB_points.y = OBB.minPoint.y; OBB_points.z = OBB.maxPoint.z; OBB.cornerPoints.push_back(OBB_points); OBB_points.x = OBB.maxPoint.x; OBB_points.y = OBB.minPoint.y; OBB_points.z = OBB.minPoint.z; OBB.cornerPoints.push_back(OBB_points); OBB_points.x = OBB.maxPoint.x; OBB_points.y = OBB.maxPoint.y; OBB_points.z = OBB.minPoint.z; OBB.cornerPoints.push_back(OBB_points); pcl::transformPointCloud(OBB.cornerPoints, OBB.cornerPoints, projectionTransform.inverse()); OBB.center.x = 0; OBB.center.y = 0; OBB.center.z = 0; for (int i = 0; i < OBB.cornerPoints.size(); i++) { OBB.center.x += OBB.cornerPoints[i].x; OBB.center.y += OBB.cornerPoints[i].y; OBB.center.z += OBB.cornerPoints[i].z; } OBB.center.x = OBB.center.x / OBB.cornerPoints.size(); OBB.center.y = OBB.center.y / OBB.cornerPoints.size(); OBB.center.z = OBB.center.z / OBB.cornerPoints.size(); } double model_to_scene::overlapPortion(const pcl::PointCloud &source, const pcl::PointCloud &target, const double &max_dist) { if (source.size() == 0 || target.size() == 0) return -1; pcl::PointCloud::Ptr target_cloud(new pcl::PointCloud); pcl::PointCloud::Ptr source_cloud(new pcl::PointCloud); pcl::copyPointCloud(target, *target_cloud); pcl::copyPointCloud(source, *source_cloud); pcl::KdTreeFLANN kdtree; kdtree.setInputCloud(target_cloud); std::vector pointIdxNKNSearch(1); std::vector pointNKNSquaredDistance(1); int overlap_Points = 0; for (int i = 0; i < source.size(); ++i) { if (kdtree.nearestKSearch(source_cloud->points[i], 1, pointIdxNKNSearch, pointNKNSquaredDistance) > 0) { if(sqrt(pointNKNSquaredDistance[0]) < max_dist) overlap_Points++; } } //calculating the mean distance double portion = (double) overlap_Points / source.size(); return portion; } void model_to_scene::coarseToFineRegistration(const pcl::PointCloud &sourceCloud, const pcl::PointCloud &modelCloud, const pcl::PointCloud &targetCloud, pcl::PointCloud ®isted_source) { pcl::PointCloud::Ptr source (new pcl::PointCloud); pcl::PointCloud::Ptr model (new pcl::PointCloud); pcl::PointCloud::Ptr target (new pcl::PointCloud); //pcl::copyPointCloud(model, *targetCloud); boundingBBox source_OBB, target_OBB; computeOBB(sourceCloud, source_OBB); computeOBB(targetCloud, target_OBB); pcl::transformPointCloud(sourceCloud, *source, source_OBB.toOrigin); pcl::transformPointCloud(modelCloud, *model, source_OBB.toOrigin); pcl::transformPointCloud(targetCloud, *target, target_OBB.toOrigin); double bestScore = -9999999; Eigen::Matrix4f bestCoarseMat (Eigen::Matrix4f::Identity());; Eigen::Matrix4f bestFineMat (Eigen::Matrix4f::Identity());; for(double RX = 0; RX <= M_PI; RX+=M_PI/2) for(double RY = 0; RY <= M_PI; RY+=M_PI/2) for(double RZ = 0; RZ <= M_PI; RZ+=M_PI) { pcl::PointCloud::Ptr rot_source (new pcl::PointCloud); Eigen::Affine3f ROT = Eigen::Affine3f::Identity(); ROT.rotate (Eigen::AngleAxisf (RX, Eigen::Vector3f::UnitX())); ROT.rotate (Eigen::AngleAxisf (RY, Eigen::Vector3f::UnitY())); ROT.rotate (Eigen::AngleAxisf (RZ, Eigen::Vector3f::UnitZ())); pcl::transformPointCloud (*source, *rot_source, ROT); pcl::IterativeClosestPoint icp; icp.setInputSource(rot_source); icp.setInputTarget(target); icp.setMaximumIterations (100); icp.setMaxCorrespondenceDistance(0.2); icp.setRANSACOutlierRejectionThreshold(1); icp.align(registed_source); double overlap_dst_thresh = 0.03; double overlapScore = overlapPortion(*target, registed_source, overlap_dst_thresh); std::cerr << "overlap score: " << overlapScore << "\n"; //if(overlapScore < overlap_score_thresh) continue; if(bestScore < overlapScore) { bestCoarseMat = ROT.matrix(); bestFineMat = icp.getFinalTransformation(); bestScore = overlapScore; } } Eigen::Matrix4f finalMat = bestFineMat*bestCoarseMat*target_OBB.toOrigin; pcl::transformPointCloud(*model, registed_source, finalMat.inverse()); } ================================================ FILE: obj_pose_est/srv/ObjectRPE.srv ================================================ string ObjectRPE_dir string dataset string data_dir int64 num_frames int64 num_keyframes --- int64 ouput